This ROS package is a bridge that enables two-way communication between ROS and CARLA. The information from the CARLA server is translated to ROS topics. In the same way, the messages sent between nodes in ROS get translated to commands to be applied in CARLA.
This version requires CARLA 0.9.13
- Provide Sensor Data (Lidar, Semantic lidar, Cameras (depth, segmentation, rgb, dvs), GNSS, Radar, IMU)
- Provide Object Data (Transforms (via tf), Traffic light status, Visualization markers, Collision, Lane invasion)
- Control AD Agents (Steer/Throttle/Brake)
- Control CARLA (Play/pause simulation, Set simulation parameters)
Installation instructions and further documentation of the ROS bridge and additional packages are found here.
carla_spawn_objects/carla_spawn_objects.py L49 : Fixed bag to load ego vehicle definition file
self.objects_definition_file = self.get_param('objects_definition_file', '<path-to-this-pkg>/carla_spawn_objects/config/objects.json')
pcl_recorder/src/PclRecorderROS2.cpp L29 : fixed build error
# transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration(1)));
transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration::from_seconds(1)));
# sub_opt.callback_group = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
sub_opt.callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
carla_ros_bridge/bridge.py L430 : fixed map loading bag
# if "town" in parameters and not parameters['passive']:
# if parameters["town"].endswith(".xodr"):
# carla_bridge.loginfo(
# "Loading opendrive world from file '{}'".format(parameters["town"]))
# with open(parameters["town"]) as od_file:
# data = od_file.read()
# carla_world = carla_client.generate_opendrive_world(str(data))
# else:
# if carla_world.get_map().name != parameters["town"]:
# carla_bridge.loginfo("Loading town '{}' (previous: '{}').".format(
# parameters["town"], carla_world.get_map().name))
# carla_world = carla_client.load_world(parameters["town"])
# carla_world.tick()
carla_spawn_objects/config/objects.json : Remove tf sensor
ros_compatibility/src/ros_compatibility/node.py L137 : Fix error of /use_sim_time
param = Parameter("use_sim_time", Parameter.Type.BOOL, True)
# param = Parameter("use_sim_time", Parameter.Type.BOOL, True)
super(CompatibleNode, self).__init__(
name,
allow_undeclared_parameters=True,
automatically_declare_parameters_from_overrides=True,
parameter_overrides=[param],
# automatically_declare_parameters_from_overrides=True,
automatically_declare_parameters_from_overrides=False,
# parameter_overrides=[param],
parameter_overrides=[],
carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py L41 : Remove function that change ego_vehicle position by /initial_pose
# launch.actions.IncludeLaunchDescription(
# launch.launch_description_sources.PythonLaunchDescriptionSource(
# os.path.join(get_package_share_directory(
# 'carla_spawn_objects'), 'set_initial_pose.launch.py')
# ),
# launch_arguments={
# 'role_name': launch.substitutions.LaunchConfiguration('role_name'),
# 'control_id': launch.substitutions.LaunchConfiguration('control_id')
# }.items()
# )