Skip to content

Commit

Permalink
Refactored instances of CarlaEgoVehicleControl and it's topic
Browse files Browse the repository at this point in the history
  • Loading branch information
AhmadBajwaCS committed Nov 17, 2023
1 parent 2e9b235 commit f783715
Show file tree
Hide file tree
Showing 13 changed files with 24 additions and 24 deletions.
2 changes: 1 addition & 1 deletion docs/Controls/epas.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ The Electric Power Assisted Steering (EPAS) node provides an interface between R
---

### In:
- **/carla/hero/vehicle_control_cmd** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/vehicle/control** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/clock** [*Clock*](https://docs.ros2.org/galactic/api/rosgraph_msgs/msg/Clock.html)
- **/guardian/mode** [*Mode*](../messages.md#mode)

Expand Down
2 changes: 1 addition & 1 deletion docs/Controls/joy_translation.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ Converts [*joy*](https://docs.ros.org/en/api/sensor_msgs/html/msg/Joy.html) mess
- **/guardian/mode** [*Mode*](../messages.md#mode)

### Out:
- **/carla/hero/vehicle_control_cmd** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/vehicle/control** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/requested_mode** [*Mode*](../messages.md#mode)
- **/node_statuses** [*DiagnosticStatus*](https://docs.ros2.org/galactic/api/diagnostic_msgs/msg/DiagnosticStatus.html)

Expand Down
4 changes: 2 additions & 2 deletions docs/Controls/linear_actuator.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ This node's responsible for our brake system. It communicates via CAN bus with a
---

### In:
- **/carla/hero/vehicle_control_cmd** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/vehicle/control** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/clock** [*Clock*](https://docs.ros2.org/galactic/api/rosgraph_msgs/msg/Clock.html)
- **/guardian/mode** [*Mode*](../messages.md#mode)

Expand All @@ -29,7 +29,7 @@ This node's responsible for our brake system. It communicates via CAN bus with a
### connectToBus(self)
Attempts to establish a connection to the CAN bus that controls our linear actuator.

### sendBrakeControl(self, msg: CarlaEgoVehicleControl)
### sendBrakeControl(self, msg: VehicleControl)
Calculates a position command from an inputted brake value and calls [`sendToPosition()`](#sendtopositionself-pos-float-bus-canbus).

### enableClutch(self, bus: can.Bus)
Expand Down
4 changes: 2 additions & 2 deletions docs/Controls/mcu_interface.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ Serves as our interface between Navigator (ROS) and our Adafruit Grand Central M
---

### In:
- **/carla/hero/vehicle_control_cmd** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/vehicle/control** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/guardian/mode** [*Mode*](../messages.md#mode)

### Out:
Expand All @@ -29,4 +29,4 @@ Serves as our interface between Navigator (ROS) and our Adafruit Grand Central M
Other than initializing the ROS node, it attempts to establish a serial connection to the MCU

### publishCommand(self)
Using an inputted throttle command via the */carla/hero/vehicle_control_cmd* topic, it parses, encodes, and writes the throttle value into serial. The format we use is `"s{throttle}e\r"`
Using an inputted throttle command via the */vehicle/control* topic, it parses, encodes, and writes the throttle value into serial. The format we use is `"s{throttle}e\r"`
6 changes: 3 additions & 3 deletions docs/Planning/airbag.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,12 @@ Airbags extend in front of the vehicle, and slightly to either side.

### In:
- **/lidar/filtered** [*PointCloud2*](https://docs.ros2.org/latest/api/sensor_msgs/msg/PointCloud.html)
- **/control/unlimited** [*CarlaEgoVehicleControl*](../messages.md#vehiclecontrol)
- **/control/unlimited** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/carla/hero/speedometer** [*CarlaSpeedometer*](../messages.md#carlaspeedometer)
- **/clock** [*Clock*](https://docs.ros2.org/galactic/api/rosgraph_msgs/msg/Clock.html)

### Out:
- **/carla/hero/vehicle_control_cmd** [*CarlaEgoVehicleControl*](../messages.md#vehiclecontrol)
- **/vehicle/control** [*VehicleControl*](../messages.md#vehiclecontrol)
- **/status/airbags** [*DiagnosticStatus*](https://docs.ros2.org/galactic/api/diagnostic_msgs/msg/DiagnosticStatus.html)
- **/visuals/airbags** [*Marker*](https://docs.ros2.org/galactic/api/visualization_msgs/msg/Marker.html)
- **/planning/current_airbag** [*String*](https://docs.ros2.org/foxy/api/std_msgs/msg/String.html)
Expand All @@ -48,6 +48,6 @@ Maps distance to max speed, limiting speed as little as possible.
### lidarCb(self, msg: PointCloud2)
Considers points in front of the car and not too far off to the side. It assume car is 2 meters wide.

### commandCb(self, msg: CarlaEgoVehicleControl)
### commandCb(self, msg: VehicleControl)
Checks if current speed is greater than speed limit, prints warning and applies brake proportionally to speed over limit.

Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
Controller for the hoco parade that follows our flag
'''

from carla_msgs.msg import CarlaEgoVehicleControl
from carla_msgs.msg import VehicleControl
from geometry_msgs.msg import TransformStamped
from rosgraph_msgs.msg import Clock
from rclpy.node import Node
Expand Down Expand Up @@ -45,7 +45,7 @@ def __init__(self):

# Publisher
self.throttle_pub = self.create_publisher(
CarlaEgoVehicleControl, '/carla/hero/vehicle_control_cmd', 10)
VehicleControl, '/vehicle/control', 10)

# Debug publisher
self.transformed_lidar_pub = self.create_publisher(PointCloud2, '/lidar_tfed', 1)
Expand Down Expand Up @@ -118,7 +118,7 @@ def pointclouds_cb(self, msg: PointCloud2):
steer = self.Kp_Steer * error_y

# Set msg fields and publish throttle value
throttle_msg = CarlaEgoVehicleControl()
throttle_msg = VehicleControl()

if throttle < 0.:
throttle = 0.
Expand Down
2 changes: 1 addition & 1 deletion src/msg/navigator_msgs/msg/VehicleControl.msg
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
#
# This represents a vehicle control message sent by Navigator (taken directly from Carla's CarlaEgoVehicleControl.msg)
# This represents a vehicle control message sent by Navigator (taken directly from Carla's VehicleControl.msg)

std_msgs/Header header

Expand Down
2 changes: 1 addition & 1 deletion src/msg/ros-carla-msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ set(SERVICE_FILES SpawnObject.srv DestroyObject.srv GetBlueprints.srv)

set(MSG_FILES
CarlaBoundingBox.msg
CarlaEgoVehicleControl.msg
VehicleControl.msg
CarlaEgoVehicleStatus.msg
CarlaEgoVehicleInfoWheel.msg
CarlaEgoVehicleInfo.msg
Expand Down
2 changes: 1 addition & 1 deletion src/msg/ros-carla-msgs/msg/CarlaEgoVehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,4 @@ geometry_msgs/Accel acceleration
geometry_msgs/Quaternion orientation

# the current control values, as reported by Carla
CarlaEgoVehicleControl control
VehicleControl control
2 changes: 1 addition & 1 deletion src/planning/rtp/rtp/rtp_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
import random
import time
from geometry_msgs.msg import PoseStamped, Quaternion, Point
#from carla_msgs.msg import CarlaEgoVehicleControl, CarlaSpeedometer
#from carla_msgs.msg import VehicleControl, CarlaSpeedometer
from navigator_msgs.msg import VehicleControl, VehicleSpeed
from std_msgs.msg import String, ColorRGBA
from sensor_msgs.msg import Imu
Expand Down
6 changes: 3 additions & 3 deletions src/safety/airbags/airbags/airbag_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
'''

from matplotlib import pyplot as plt
from carla_msgs.msg import CarlaEgoVehicleControl
from carla_msgs.msg import VehicleControl
from navigator_msgs.msg import CarlaSpeedometer, VehicleControl
from diagnostic_msgs.msg import DiagnosticStatus
from nav_msgs.msg import OccupancyGrid
Expand Down Expand Up @@ -35,7 +35,7 @@ def __init__(self):
PointCloud2, '/lidar/filtered', self.lidarCb, 1)

self.command_sub = self.create_subscription(
CarlaEgoVehicleControl, '/control/unlimited', self.commandCb, 1)
VehicleControl, '/control/unlimited', self.commandCb, 1)

self.speed_sub = self.create_subscription(
CarlaSpeedometer, '/carla/hero/speedometer', self.speedCb, 1)
Expand Down Expand Up @@ -100,7 +100,7 @@ def lidarCb(self, msg: PointCloud2):

self.speed_limit = self.distanceToSpeedLimit(closest_x)

def commandCb(self, msg: CarlaEgoVehicleControl):
def commandCb(self, msg: VehicleControl):

if self.current_speed > self.speed_limit:
speed_over_limit = self.current_speed - self.speed_limit
Expand Down
2 changes: 1 addition & 1 deletion src/safety/guardian/guardian/guardian_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
from rosgraph_msgs.msg import Clock
import time

from carla_msgs.msg import CarlaEgoVehicleControl
from carla_msgs.msg import VehicleControl
from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray, KeyValue
from nav_msgs.msg import Path
from navigator_msgs.msg import Mode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@
/joy (sensor_msgs/Joy)
Publishes to:
/carla/hero/vehicle_control_cmd (CarlaEgoVehicleControl)
/vehicle/control (VehicleControl)
'''

import numpy as np
from rosgraph_msgs.msg import Clock
import time

from carla_msgs.msg import CarlaEgoVehicleControl
from carla_msgs.msg import VehicleControl
from navigator_msgs.msg import CarlaSpeedometer
from diagnostic_msgs.msg import DiagnosticStatus, KeyValue
from navigator_msgs.msg import Mode
Expand All @@ -71,7 +71,7 @@ def __init__(self):
Clock, '/clock', self.clockCb, 10)

self.command_pub = self.create_publisher(
CarlaEgoVehicleControl, '/carla/hero/vehicle_control_cmd', 10)
VehicleControl, '/vehicle/control', 10)

self.requested_mode_pub = self.create_publisher(
Mode, '/requested_mode', 1)
Expand Down Expand Up @@ -137,7 +137,7 @@ def getSpeedAdjustedSteering(self, joystick_pos: float) -> float:
return steer

def joyCb(self, msg: Joy):
command_msg = CarlaEgoVehicleControl()
command_msg = VehicleControl()

self.status = self.initStatusMsg()

Expand Down

0 comments on commit f783715

Please sign in to comment.