From 1f669b4aca1a433a38020b7f00c0478fdc1c89cd Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 15 Mar 2024 13:48:15 +0900 Subject: [PATCH 01/50] Added CARLA Bridge --- .../GNSS_Interface/CMakeLists.txt | 38 ++++ .../CARLA_Autoware/GNSS_Interface/README.md | 4 + .../gnss_interface/gnss_interface_node.hpp | 105 +++++++++ .../launch/gnss_interface.launch.xml | 14 ++ .../CARLA_Autoware/GNSS_Interface/package.xml | 29 +++ .../gnss_interface/gnss_interface_node.cpp | 84 +++++++ bridge/CARLA_Autoware/LICENSE | 21 ++ bridge/CARLA_Autoware/README.md | 58 +++++ .../carla_autoware/CMakeLists.txt | 52 +++++ .../carla_autoware/config/objects.json | 118 ++++++++++ .../launch/carla_autoware.launch.xml | 11 + .../launch/carla_ros.launch.xml | 52 +++++ .../launch/e2e_simulator.launch.xml | 88 ++++++++ .../CARLA_Autoware/carla_autoware/package.xml | 46 ++++ .../carla_autoware/resource/carla_autoware | 0 .../CARLA_Autoware/carla_autoware/setup.cfg | 4 + bridge/CARLA_Autoware/carla_autoware/setup.py | 44 ++++ .../src/carla_autoware/carla_autoware.py | 134 +++++++++++ .../.markdown-link-check.json | 13 ++ .../.markdownlint.yaml | 9 + .../.pre-commit-config-optional.yaml | 6 + .../.pre-commit-config.yaml | 68 ++++++ .../carla_sensor_kit_launch/.prettierignore | 2 + .../carla_sensor_kit_launch/.prettierrc.yaml | 20 ++ .../carla_sensor_kit_launch/.yamllint.yaml | 23 ++ .../CODE_OF_CONDUCT.md | 132 +++++++++++ .../carla_sensor_kit_launch/CONTRIBUTING.md | 3 + .../carla_sensor_kit_launch/DISCLAIMER.md | 46 ++++ .../carla_sensor_kit_launch/LICENSE | 201 +++++++++++++++++ .../carla_sensor_kit_launch/NOTICE | 8 + .../carla_sensor_kit_launch/README.md | 3 + .../build_depends.repos | 9 + .../CMakeLists.txt | 11 + .../config/sensor_kit_calibration.yaml | 92 ++++++++ .../config/sensors_calibration.yaml | 15 ++ .../carla_sensor_kit_description/package.xml | 17 ++ .../urdf/sensor_kit.xacro | 209 ++++++++++++++++++ .../urdf/sensors.xacro | 30 +++ .../carla_sensor_kit_launch/CMakeLists.txt | 16 ++ .../sensor_kit.param.yaml | 0 .../data/traffic_light_camera.yaml | 45 ++++ .../launch/imu.launch.xml | 14 ++ .../launch/lidar.launch.xml | 43 ++++ .../launch/pointcloud_preprocessor.launch.py | 110 +++++++++ .../launch/sensing.launch.xml | 33 +++ .../carla_sensor_kit_launch/package.xml | 26 +++ .../common_carla_sensor_launch/CMakeLists.txt | 14 ++ .../launch/velodyne_lidar.launch.xml | 12 + .../launch/velodyne_node_container.launch.py | 208 +++++++++++++++++ .../common_carla_sensor_launch/package.xml | 22 ++ .../carla_sensor_kit_launch/setup.cfg | 15 ++ .../pointcloud_interface/CMakeLists.txt | 69 ++++++ .../pointcloud_interface/README.md | 4 + .../pointcloud_interface_node.hpp | 31 +++ .../launch/pointcloud_interface.xml | 3 + .../pointcloud_interface/package.xml | 35 +++ .../pointcloud_interface_node.cpp | 55 +++++ 57 files changed, 2574 insertions(+) create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/README.md create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/package.xml create mode 100644 bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp create mode 100644 bridge/CARLA_Autoware/LICENSE create mode 100644 bridge/CARLA_Autoware/README.md create mode 100644 bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/carla_autoware/config/objects.json create mode 100644 bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_autoware/package.xml create mode 100644 bridge/CARLA_Autoware/carla_autoware/resource/carla_autoware create mode 100644 bridge/CARLA_Autoware/carla_autoware/setup.cfg create mode 100644 bridge/CARLA_Autoware/carla_autoware/setup.py create mode 100644 bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml create mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/README.md create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/package.xml create mode 100644 bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp diff --git a/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt b/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt new file mode 100644 index 0000000000000..a817198813e60 --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt @@ -0,0 +1,38 @@ +cmake_minimum_required(VERSION 3.5) +project(gnss_interface) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + + +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) +endif() + + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +find_package(PkgConfig REQUIRED) +pkg_check_modules(PROJ REQUIRED proj) + +ament_auto_add_library(gnss_interface SHARED + src/gnss_interface/gnss_interface_node.cpp +) + +target_link_libraries(gnss_interface ${PROJ_LIBRARIES}) + +rclcpp_components_register_node(gnss_interface + PLUGIN "GnssInterface" + EXECUTABLE gnss_interface_node +) + +ament_auto_package( + INSTALL_TO_SHARE + launch +) + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/README.md b/bridge/CARLA_Autoware/GNSS_Interface/README.md new file mode 100644 index 0000000000000..356de168b8d13 --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/README.md @@ -0,0 +1,4 @@ +# gnss Interface Node + +Convert GNSS CARLA messages to pose and pose with covariance + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp b/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp new file mode 100644 index 0000000000000..ec2c9f97b4caa --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp @@ -0,0 +1,105 @@ + +#ifndef GNSS_ +#define GNSS_ + +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include +#include +#include +#include + +class GnssInterface : public rclcpp::Node +{ +public: + explicit GnssInterface(const rclcpp::NodeOptions & node_options); + virtual ~GnssInterface(); + std::string tf_output_frame_; + +private: + + rclcpp::Subscription::SharedPtr sub_gnss_fix; + rclcpp::Publisher::SharedPtr pup_pose; + rclcpp::Publisher::SharedPtr pup_pose_with_cov; + + + void GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg); + +}; + +namespace interface { + namespace gnss { + +class GPSPoint +{ +public: + double x, y, z; + double lat, lon, alt; + double dir, a; + + GPSPoint() + { + x = y = z = 0; + lat = lon = alt = 0; + dir = a = 0; + } + + GPSPoint(const double& x, const double& y, const double& z, const double& a) + { + this->x = x; + this->y = y; + this->z = z; + this->a = a; + + lat = 0; + lon = 0; + alt = 0; + dir = 0; + } + + std::string ToString() + { + std::stringstream str; + str.precision(12); + str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; + str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; + return str.str(); + } +}; + + +class WayPoint +{ +public: + GPSPoint pos; + WayPoint() + { + } + + WayPoint(const double& x, const double& y, const double& z, const double& a) + { + pos.x = x; + pos.y = y; + pos.z = z; + pos.a = a; + } +}; + +class MappingUtils { +public: + MappingUtils(); + virtual ~MappingUtils(); + + static void llaToxyz(const std::string& proj_str, const WayPoint& origin, const double& lat, + const double& lon, const double& alt, double& x_out, double& y_out, double& z_out); +}; + +} +} + +#endif + + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml b/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml new file mode 100644 index 0000000000000..5a14dbc2ed04b --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/package.xml b/bridge/CARLA_Autoware/GNSS_Interface/package.xml new file mode 100644 index 0000000000000..0793b71f731bd --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/package.xml @@ -0,0 +1,29 @@ + + + + gnss_interface + 1.0.0 + Convert GNSS CARLA messages to pose and pose with covariance + Muhammad Raditya Giovanni + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + angles + diagnostic_updater + geometry_msgs + message_filters + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_ros + tinyxml + proj + + + ament_cmake + + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp b/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp new file mode 100644 index 0000000000000..d4d1a29a31eae --- /dev/null +++ b/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp @@ -0,0 +1,84 @@ +#include "gnss_interface/gnss_interface_node.hpp" +#include + + +namespace interface { + namespace gnss { + +using namespace std; + + +MappingUtils::MappingUtils() { +} + +MappingUtils::~MappingUtils() { +} + + +void MappingUtils::llaToxyz(const std::string& proj_str, const WayPoint& origin, + const double& lat, const double& lon, const double& alt, + double& x_out, double& y_out, double& z_out) { + if (proj_str.size() < 8) return; + + PJ_CONTEXT *C = proj_context_create(); + PJ *P = proj_create_crs_to_crs(C, "EPSG:4326", proj_str.c_str(), NULL); + + if (P == 0) return; + + PJ_COORD gps_degrees = proj_coord(lat, lon, alt, 0); + PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); + x_out = xyz_out.enu.e + origin.pos.x; + y_out = xyz_out.enu.n + origin.pos.y; + z_out = xyz_out.enu.u + origin.pos.z; + + proj_destroy(P); + proj_context_destroy(C); +} +} +} + + +void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg) +{ + geometry_msgs::msg::PoseStamped pose_; + geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; + interface::gnss::WayPoint origin, p; + interface::gnss::MappingUtils::llaToxyz( + "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs", + origin, msg->latitude, msg->longitude, msg->altitude, + p.pos.x, p.pos.y, p.pos.z); + pose_.header = msg->header; + pose_.header.frame_id = "map"; + pose_.pose.position.x = p.pos.x; + pose_.pose.position.y = p.pos.y; + pose_.pose.position.z = p.pos.z; + + pose_cov_.header = pose_.header; + pose_cov_.pose.pose = pose_.pose; + + pup_pose->publish(pose_); + pup_pose_with_cov->publish(pose_cov_); + +} + +GnssInterface::~GnssInterface() +{ + +} + +GnssInterface::GnssInterface(const rclcpp::NodeOptions & node_options) +: Node("gnss_interface_node", node_options), tf_output_frame_("base_link") +{ + sub_gnss_fix = this->create_subscription( + "carla/ego_vehicle/gnss", 1, + std::bind(&GnssInterface::GnssCallBack, this, std::placeholders::_1)); + + pup_pose = this->create_publisher( + "/sensing/gnss/pose", 1); + pup_pose_with_cov = this->create_publisher( + "/sensing/gnss/pose_with_covariance", 1); +} + + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(GnssInterface) diff --git a/bridge/CARLA_Autoware/LICENSE b/bridge/CARLA_Autoware/LICENSE new file mode 100644 index 0000000000000..b3c8c7e3fc138 --- /dev/null +++ b/bridge/CARLA_Autoware/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2024 Giovanni Muhammad Raditya + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/bridge/CARLA_Autoware/README.md b/bridge/CARLA_Autoware/README.md new file mode 100644 index 0000000000000..4d616e4f6723f --- /dev/null +++ b/bridge/CARLA_Autoware/README.md @@ -0,0 +1,58 @@ +# CARLA_Autoware +# ROS2/Autoware.universe bridge for CARLA simulator + + +### Thanks to https://github.com/gezp for ROS2 Humble support for CARLA ROS bridge. + This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). (https://github.com/gezp for ROS2 Humble) +- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.14-ubuntu-22.04). +- Add the egg file to the folder: ../CARLA_0.9.14/PythonAPI/carla/dist +- And install the wheel using pip. + +# Environment +|ubuntu|ros|carla|autoware| +|:---:|:---:|:---:|:---:| +|22.04|humble|0.9.14|universe/master| + +# Setup +## install +* [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) +* [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) +* [autoware containts](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) + 1. Download maps (y-axis inverted version) to arbitaly location + 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) + 3. Create ``map_projector_info.yaml`` and add ``projector_type: local`` on the first line. +* Clone this repositories and ROSBridge + ``` + git clone https://github.com/mraditya01/CARLA_Autoware.git + git clone --recurse-submodules https://github.com/gezp/carla_ros.git -b humble-carla-0.9.14 + ``` + * Copy the files (sensor_kit_calibration.yaml, sensors.calibration.yaml) from folder "GNSS_interface/src/carla_sensor_kit_launch/carla_sensor_kit_description/config" to "src/param/autoware_individual_params/carla_sensor_kit". + + +## build +```bash +cd colcon_ws +colcon build --symlink-install +``` + +# Run +1. Run carla, change map, spawn object if you need +```bash +cd CARLA +./CarlaUE4.sh -prefernvidia -quality-level=Low +``` + +2. Run ros nodes +```bash +ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit +``` + +3. Set initial pose (Init by GNSS) +4. Set goal position +5. Wait for planning +6. Engage + +# Tips +* If you want to edit the sensors configuration used in CARLA, edit ``objects.json`` located in ``carla_autoware/config``. +* You will also need to edit the ``carla_sensor_kit_description`` if you change the sensor configuration. +* Misalignment might occurs during initialization, pressing ``init by gnss`` button should fix it. \ No newline at end of file diff --git a/bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt b/bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt new file mode 100644 index 0000000000000..deb641375684e --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 3.8) +project(carla_autoware) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + + + +# find dependencies +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(sensor_msgs_py REQUIRED) +find_package(datetime REQUIRED) + +find_package(rclpy REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(carla_msgs REQUIRED) +find_package(autoware_auto_vehicle_msgs REQUIRED) +find_package(autoware_auto_control_msgs REQUIRED) +find_package(tier4_debug_msgs REQUIRED) +find_package(tier4_system_msgs REQUIRED) +find_package(autoware_adapi_v1_msgs REQUIRED) +find_package(transform3d REQUIRED) +find_package(math REQUIRED) +find_package(numpy REQUIRED) +find_package(carla_data_provider REQUIRED) + + + + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +ament_export_dependencies(rclpy) + +# Install launch files. +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + +ament_auto_package( + launch + resource + src +) +ament_package() diff --git a/bridge/CARLA_Autoware/carla_autoware/config/objects.json b/bridge/CARLA_Autoware/carla_autoware/config/objects.json new file mode 100644 index 0000000000000..ff458c22276db --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/config/objects.json @@ -0,0 +1,118 @@ +{ + "objects": + [ + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" + }, + { + "type": "vehicle.toyota.prius", + "id": "ego_vehicle", + "sensors": + [ + { + "type": "sensor.camera.rgb", + "id": "rgb_front", + "spawn_point": {"x": 0.7, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "image_size_x": 1280, + "image_size_y": 720, + "fov": 100.0 + }, + { + "type": "sensor.camera.rgb", + "id": "rgb_view", + "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0}, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "attached_objects": + [ + { + "type": "actor.pseudo.control", + "id": "control" + } + ] + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "noise_stddev": 0.0 + }, + { + "type": "sensor.opendrive_map", + "id": "OpenDRIVE", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0} + }, + + { + "type": "sensor.other.gnss", + "id": "gnss", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6}, + "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0, + "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0 + }, + { + "type": "sensor.other.imu", + "id": "imu", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0, + "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0, + "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 + }, + { + "type": "sensor.other.collision", + "id": "collision", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} + }, + { + "type": "sensor.other.lane_invasion", + "id": "lane_invasion", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} + }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "actor.pseudo.control", + "id": "control" + } + ] + } + ] +} diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml new file mode 100644 index 0000000000000..b84bdd889d53e --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml new file mode 100644 index 0000000000000..46bdd4bb86cd4 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml new file mode 100644 index 0000000000000..345054570bde7 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_autoware/package.xml b/bridge/CARLA_Autoware/carla_autoware/package.xml new file mode 100644 index 0000000000000..10b5b5b6101be --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/package.xml @@ -0,0 +1,46 @@ + + + carla_autoware + 0.0.0 + The carla_manual_control package + CARLA Simulator Team + MIT + + std_msgs + ros_compatibility + geometry_msgs + tf2 + tf2_ros + sensor_msgs + sensor_msgs_py + + nav_msgs + carla_msgs + autoware_auto_vehicle_msgs + autoware_auto_control_msgs + rclpy + numpy + datetime + carla_data_provider + astuff_sensor_msgs + + + math + transform3d + + + + + ros2launch + ament_cmake + + ament_lint_auto + ament_lint_common + + + + + + ament_python + + diff --git a/bridge/CARLA_Autoware/carla_autoware/resource/carla_autoware b/bridge/CARLA_Autoware/carla_autoware/resource/carla_autoware new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.cfg b/bridge/CARLA_Autoware/carla_autoware/setup.cfg new file mode 100644 index 0000000000000..5cb120ba598b4 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/carla_autoware +[install] +install_scripts=$base/lib/carla_autoware \ No newline at end of file diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.py b/bridge/CARLA_Autoware/carla_autoware/setup.py new file mode 100644 index 0000000000000..f0e39dcba107c --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/setup.py @@ -0,0 +1,44 @@ + + +""" +Setup for carla_manual_control +""" +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup + + d = generate_distutils_setup(packages=['carla_autoware'], package_dir={'': 'src'}) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_autoware' + + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, glob('config/*.json')), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.xml')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='mradityagio', + maintainer_email='mradityagio@gmail.com', + description='CARLA ROS2 bridge for AUTOWARE', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': ['carla_autoware = carla_autoware.carla_autoware:main'], + }, + package_dir={'': 'src'}, + ) diff --git a/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py new file mode 100644 index 0000000000000..471d0248318ef --- /dev/null +++ b/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -0,0 +1,134 @@ +import rclpy +from rclpy.node import Node +from autoware_auto_vehicle_msgs.msg import VelocityReport, SteeringReport, ControlModeReport, GearReport +from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleControl +from autoware_auto_control_msgs.msg import AckermannControlCommand +from sensor_msgs.msg import Imu, PointCloud2 +import carla +from rclpy.qos import QoSProfile +import math +from transforms3d.euler import quat2euler +from sensor_msgs_py.point_cloud2 import create_cloud +import threading + + +class CarlaVehicleInterface(Node): + def __init__(self): + rclpy.init(args=None) + + super().__init__('carla_vehicle_interface_node') + + client = carla.Client("localhost", 2000) + client.set_timeout(20) + + self._world = client.get_world() + self.current_vel = 0.0 + self.target_vel = 0.0 + self.vel_diff = 0.0 + self.current_control = carla.VehicleControl() + self.ros2_node = rclpy.create_node("carla_autoware") + + self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) + self.spin_thread.start() + + # Publishes Topics used for AUTOWARE + self.pub_vel_state = self.ros2_node.create_publisher(VelocityReport, '/vehicle/status/velocity_status', 1) + self.pub_steering_state = self.ros2_node.create_publisher(SteeringReport, '/vehicle/status/steering_status', 1) + self.pub_ctrl_mode = self.ros2_node.create_publisher(ControlModeReport, '/vehicle/status/control_mode', 1) + self.pub_gear_state = self.ros2_node.create_publisher(GearReport, '/vehicle/status/gear_status', 1) + self.pub_control = self.ros2_node.create_publisher(CarlaEgoVehicleControl, '/carla/ego_vehicle/vehicle_control_cmd', 1) + self.vehicle_imu_publisher = self.ros2_node.create_publisher(Imu, '/sensing/imu/tamagawa/imu_raw', 1) + self.sensing_cloud_publisher = self.ros2_node.create_publisher(PointCloud2, '/carla_pointcloud', 1) + + # Subscribe Topics used in Control + self.sub_status = self.ros2_node.create_subscription(CarlaEgoVehicleStatus, '/carla/ego_vehicle/vehicle_status', self.ego_status_callback, 1) + self.sub_control = self.ros2_node.create_subscription(AckermannControlCommand, '/control/command/control_cmd', self.control_callback, qos_profile=QoSProfile(depth=1)) + self.sub_imu = self.ros2_node.create_subscription(Imu, '/carla/ego_vehicle/imu', self.publish_imu, 1) + self.sub_lidar = self.ros2_node.create_subscription(PointCloud2, '/carla/ego_vehicle/lidar', self.publish_lidar, qos_profile=QoSProfile(depth=1)) + + + + + + + + def ego_status_callback(self, in_status): + """ + Callback function for CARLA Ego Vehicle Status to AUTOWARE + """ + out_vel_state = VelocityReport() + out_steering_state = SteeringReport() + out_ctrl_mode = ControlModeReport() + out_gear_state = GearReport() + + out_vel_state.header = in_status.header + out_vel_state.header.frame_id = 'base_link' + out_vel_state.longitudinal_velocity = in_status.velocity + out_vel_state.lateral_velocity = 0.0 + out_vel_state.heading_rate = 0.0 + self.current_vel = in_status.velocity + + + out_steering_state.stamp = in_status.header.stamp + out_steering_state.steering_tire_angle = (-in_status.control.steer) + + out_gear_state.stamp = in_status.header.stamp + out_gear_state.report = GearReport.DRIVE + + out_ctrl_mode.stamp = in_status.header.stamp + out_ctrl_mode.mode = ControlModeReport.AUTONOMOUS + + self.pub_vel_state.publish(out_vel_state) + self.pub_steering_state.publish(out_steering_state) + self.pub_ctrl_mode.publish(out_ctrl_mode) + self.pub_gear_state.publish(out_gear_state) + + def control_callback(self, in_cmd): + """ + Callback function for CARLA Control + """ + out_cmd = CarlaEgoVehicleControl() + self.target_vel = abs(in_cmd.longitudinal.speed) + self.vel_diff = self.target_vel - self.current_vel + + if self.vel_diff > 0: + out_cmd.throttle = 0.75 + out_cmd.brake = 0.0 + elif self.vel_diff <= 0.0: + out_cmd.throttle = 0.0 + if self.target_vel <= 0.0: + out_cmd.brake = 0.75 + elif self.vel_diff > -1: + out_cmd.brake = 0.0 + else: + out_cmd.brake = 0.01 + + out_cmd.steer = (-in_cmd.lateral.steering_tire_angle) + self.pub_control.publish(out_cmd) + + def publish_lidar(self, lidar_msg): + """ + Publish LIDAR to Interface + """ + lidar_msg.header.frame_id = "velodyne_top" + self.sensing_cloud_publisher.publish(lidar_msg) + + def publish_imu(self, imu_msg): + """ + Publish IMU to Autoware + """ + imu_msg.header.frame_id = "tamagawa/imu_link" + self.vehicle_imu_publisher.publish(imu_msg) + + def publish_gnss(self, msg): + """ + Publish GNSS to Autoware + """ + self.publisher_map.publish(msg) + + +def main(args=None): + carla_vehicle_interface = CarlaVehicleInterface() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json new file mode 100644 index 0000000000000..dec3db1ad1c8d --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json @@ -0,0 +1,13 @@ +{ + "aliveStatusCodes": [200, 206, 403], + "ignorePatterns": [ + { + "pattern": "^http://localhost" + }, + { + "pattern": "^https://github.com/.*/discussions/new" + } + ], + "retryOn429": true, + "retryCount": 10 +} diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml new file mode 100644 index 0000000000000..df1f518dc0d48 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml @@ -0,0 +1,9 @@ +# See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. +default: true +MD013: false +MD024: + siblings_only: true +MD033: false +MD041: false +MD046: false +MD049: false diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml new file mode 100644 index 0000000000000..a805f1201c414 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml @@ -0,0 +1,6 @@ +repos: + - repo: https://github.com/tcort/markdown-link-check + rev: v3.10.0 + hooks: + - id: markdown-link-check + args: [--config=.markdown-link-check.json] diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml new file mode 100644 index 0000000000000..46b8247bde927 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml @@ -0,0 +1,68 @@ +ci: + autofix_commit_msg: "ci(pre-commit): autofix" + autoupdate_commit_msg: "ci(pre-commit): autoupdate" + +repos: + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.3.0 + hooks: + - id: check-json + - id: check-merge-conflict + - id: check-toml + - id: check-xml + - id: check-yaml + - id: detect-private-key + - id: end-of-file-fixer + - id: mixed-line-ending + - id: trailing-whitespace + args: [--markdown-linebreak-ext=md] + + - repo: https://github.com/igorshubovych/markdownlint-cli + rev: v0.31.1 + hooks: + - id: markdownlint + args: [-c, .markdownlint.yaml, --fix] + + - repo: https://github.com/pre-commit/mirrors-prettier + rev: v2.7.1 + hooks: + - id: prettier + + - repo: https://github.com/adrienverge/yamllint + rev: v1.26.3 + hooks: + - id: yamllint + + - repo: https://github.com/tier4/pre-commit-hooks-ros + rev: v0.7.1 + hooks: + - id: flake8-ros + - id: prettier-xacro + - id: prettier-launch-xml + - id: prettier-package-xml + - id: ros-include-guard + - id: sort-package-xml + + - repo: https://github.com/shellcheck-py/shellcheck-py + rev: v0.8.0.4 + hooks: + - id: shellcheck + + - repo: https://github.com/scop/pre-commit-shfmt + rev: v3.5.1-1 + hooks: + - id: shfmt + args: [-w, -s, -i=4] + + - repo: https://github.com/pycqa/isort + rev: 5.10.1 + hooks: + - id: isort + + - repo: https://github.com/psf/black + rev: 22.6.0 + hooks: + - id: black + args: [--line-length=100] + +exclude: .svg diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore new file mode 100644 index 0000000000000..a3c34d00a1377 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore @@ -0,0 +1,2 @@ +*.param.yaml +*.rviz diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml new file mode 100644 index 0000000000000..e29bf32762769 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml @@ -0,0 +1,20 @@ +printWidth: 100 +tabWidth: 2 +overrides: + - files: package.xml + options: + printWidth: 1000 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.launch.xml" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.xacro" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml new file mode 100644 index 0000000000000..6228c70f02da9 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml @@ -0,0 +1,23 @@ +extends: default + +ignore: | + .clang-tidy + *.param.yaml + +rules: + braces: + level: error + max-spaces-inside: 1 # To format with Prettier + comments: + level: error + min-spaces-from-content: 1 # To be compatible with C++ and Python + document-start: + level: error + present: false # Don't need document start markers + line-length: disable # Delegate to Prettier + truthy: + level: error + check-keys: false # To allow 'on' of GitHub Actions + quoted-strings: + level: error + required: only-when-needed # To keep consistent style diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md new file mode 100644 index 0000000000000..c493cad4da591 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md @@ -0,0 +1,132 @@ +# Contributor Covenant Code of Conduct + +## Our Pledge + +We as members, contributors, and leaders pledge to make participation in our +community a harassment-free experience for everyone, regardless of age, body +size, visible or invisible disability, ethnicity, sex characteristics, gender +identity and expression, level of experience, education, socio-economic status, +nationality, personal appearance, race, caste, color, religion, or sexual +identity and orientation. + +We pledge to act and interact in ways that contribute to an open, welcoming, +diverse, inclusive, and healthy community. + +## Our Standards + +Examples of behavior that contributes to a positive environment for our +community include: + +- Demonstrating empathy and kindness toward other people +- Being respectful of differing opinions, viewpoints, and experiences +- Giving and gracefully accepting constructive feedback +- Accepting responsibility and apologizing to those affected by our mistakes, + and learning from the experience +- Focusing on what is best not just for us as individuals, but for the overall + community + +Examples of unacceptable behavior include: + +- The use of sexualized language or imagery, and sexual attention or advances of + any kind +- Trolling, insulting or derogatory comments, and personal or political attacks +- Public or private harassment +- Publishing others' private information, such as a physical or email address, + without their explicit permission +- Other conduct which could reasonably be considered inappropriate in a + professional setting + +## Enforcement Responsibilities + +Community leaders are responsible for clarifying and enforcing our standards of +acceptable behavior and will take appropriate and fair corrective action in +response to any behavior that they deem inappropriate, threatening, offensive, +or harmful. + +Community leaders have the right and responsibility to remove, edit, or reject +comments, commits, code, wiki edits, issues, and other contributions that are +not aligned to this Code of Conduct, and will communicate reasons for moderation +decisions when appropriate. + +## Scope + +This Code of Conduct applies within all community spaces, and also applies when +an individual is officially representing the community in public spaces. +Examples of representing our community include using an official e-mail address, +posting via an official social media account, or acting as an appointed +representative at an online or offline event. + +## Enforcement + +Instances of abusive, harassing, or otherwise unacceptable behavior may be +reported to the community leaders responsible for enforcement at +conduct@autoware.org. +All complaints will be reviewed and investigated promptly and fairly. + +All community leaders are obligated to respect the privacy and security of the +reporter of any incident. + +## Enforcement Guidelines + +Community leaders will follow these Community Impact Guidelines in determining +the consequences for any action they deem in violation of this Code of Conduct: + +### 1. Correction + +**Community Impact**: Use of inappropriate language or other behavior deemed +unprofessional or unwelcome in the community. + +**Consequence**: A private, written warning from community leaders, providing +clarity around the nature of the violation and an explanation of why the +behavior was inappropriate. A public apology may be requested. + +### 2. Warning + +**Community Impact**: A violation through a single incident or series of +actions. + +**Consequence**: A warning with consequences for continued behavior. No +interaction with the people involved, including unsolicited interaction with +those enforcing the Code of Conduct, for a specified period of time. This +includes avoiding interactions in community spaces as well as external channels +like social media. Violating these terms may lead to a temporary or permanent +ban. + +### 3. Temporary Ban + +**Community Impact**: A serious violation of community standards, including +sustained inappropriate behavior. + +**Consequence**: A temporary ban from any sort of interaction or public +communication with the community for a specified period of time. No public or +private interaction with the people involved, including unsolicited interaction +with those enforcing the Code of Conduct, is allowed during this period. +Violating these terms may lead to a permanent ban. + +### 4. Permanent Ban + +**Community Impact**: Demonstrating a pattern of violation of community +standards, including sustained inappropriate behavior, harassment of an +individual, or aggression toward or disparagement of classes of individuals. + +**Consequence**: A permanent ban from any sort of public interaction within the +community. + +## Attribution + +This Code of Conduct is adapted from the [Contributor Covenant][homepage], +version 2.1, available at +[https://www.contributor-covenant.org/version/2/1/code_of_conduct.html][v2.1]. + +Community Impact Guidelines were inspired by +[Mozilla's code of conduct enforcement ladder][mozilla coc]. + +For answers to common questions about this code of conduct, see the FAQ at +[https://www.contributor-covenant.org/faq][faq]. Translations are available at +[https://www.contributor-covenant.org/translations][translations]. + +[homepage]: https://www.contributor-covenant.org +[v2.1]: https://www.contributor-covenant.org/version/2/1/code_of_conduct.html +[mozilla coc]: https://github.com/mozilla/diversity +[faq]: https://www.contributor-covenant.org/faq +[translations]: https://www.contributor-covenant.org/translations diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md new file mode 100644 index 0000000000000..22c7ee28e8d9a --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md @@ -0,0 +1,3 @@ +# Contributing + +See . diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md new file mode 100644 index 0000000000000..1b5a9bbe4d981 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md @@ -0,0 +1,46 @@ +DISCLAIMER + +“Autoware” will be provided by The Autoware Foundation under the Apache License 2.0. +This “DISCLAIMER” will be applied to all users of Autoware (a “User” or “Users”) with +the Apache License 2.0 and Users shall hereby approve and acknowledge all the contents +specified in this disclaimer below and will be deemed to consent to this +disclaimer without any objection upon utilizing or downloading Autoware. + +Disclaimer and Waiver of Warranties + +1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, + EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) + including but not limited to any representation or warranty (i) of fitness or + suitability for a particular purpose contemplated by the Users, (ii) of the + expected functions, commercial value, accuracy, or usefulness of the Service, + (iii) that the use by the Users of the Service complies with the laws and + regulations applicable to the Users or any internal rules established by + industrial organizations, (iv) that the Service will be free of interruption or + defects, (v) of the non-infringement of any third party's right and (vi) the + accuracy of the content of the Services and the software itself. + +2. The Autoware Foundation shall not be liable for any damage incurred by the + User that are attributable to the Autoware Foundation for any reasons + whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR + INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. + +3. A User shall be entirely responsible for the content posted by the User and + its use of any content of the Service or the Website. If the User is held + responsible in a civil action such as a claim for damages or even in a criminal + case, the Autoware Foundation and member companies, governments and academic & + non-profit organizations and their directors, officers, employees and agents + (collectively, the “Indemnified Parties”) shall be completely discharged from + any rights or assertions the User may have against the Indemnified Parties, or + from any legal action, litigation or similar procedures. + +Indemnity + +A User shall indemnify and hold the Indemnified Parties harmless from any of +their damages, losses, liabilities, costs or expenses (including attorneys' +fees or criminal compensation), or any claims or demands made against the +Indemnified Parties by any third party, due to or arising out of, or in +connection with utilizing Autoware (including the representations and +warranties), the violation of applicable Product Liability Law of each country +(including criminal case) or violation of any applicable laws by the Users, or +the content posted by the User or its use of any content of the Service or the +Website. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE b/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE new file mode 100644 index 0000000000000..261eeb9e9f8b2 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE b/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE new file mode 100644 index 0000000000000..60fbbe96174e5 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE @@ -0,0 +1,8 @@ +carla_sensor_kit_launch +Copyright 2021 The Autoware Foundation + +This product includes software developed at +The Autoware Foundation (https://www.autoware.org/). + +This product includes code developed by TIER IV. +Copyright 2020 TIER IV, Inc. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md new file mode 100644 index 0000000000000..856700225f228 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md @@ -0,0 +1,3 @@ +# carla_sensor_kit_launch + +A sensor kit configurations for CARLA Simulator diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos b/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos new file mode 100644 index 0000000000000..08e78b602a8d0 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos @@ -0,0 +1,9 @@ +repositories: + autoware_common: + type: git + url: https://github.com/autowarefoundation/autoware_common.git + version: main + sensor_component_description: + type: git + url: https://github.com/tier4/sensor_component_description.git + version: main diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt new file mode 100644 index 0000000000000..b2b320a645d80 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.5) +project(carla_sensor_kit_description) + +find_package(ament_cmake_auto REQUIRED) + +ament_auto_find_build_dependencies() + +ament_auto_package(INSTALL_TO_SHARE + urdf + config +) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml new file mode 100644 index 0000000000000..aa2aeb5b3a42e --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml @@ -0,0 +1,92 @@ +sensor_kit_base_link: + camera0/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + camera1/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + camera2/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + camera3/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + camera4/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + camera5/camera_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + traffic_light_right_camera/camera_link: + x: -0.7 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + traffic_light_left_camera/camera_link: + x: 0.7 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + velodyne_top_base_link: + x: 0.0 + y: 0.0 + z: 1.0 + roll: 0.0 + pitch: 0.0 + yaw: 0 + velodyne_left_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + velodyne_right_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + gnss_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + tamagawa/imu_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml new file mode 100644 index 0000000000000..c25cc52357e97 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml @@ -0,0 +1,15 @@ +base_link: + sensor_kit_base_link: + x: 0.0 + y: 0.0 + z: 1.6 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 + velodyne_rear_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml new file mode 100644 index 0000000000000..638e73fb15972 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml @@ -0,0 +1,17 @@ + + + + carla_sensor_kit_description + 0.1.0 + The carla_sensor_kit_description package + Hatem Darweesh + Apache License 2.0 + + ament_cmake_auto + + velodyne_description + + + ament_cmake + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro new file mode 100644 index 0000000000000..c40b383563186 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro @@ -0,0 +1,209 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro new file mode 100644 index 0000000000000..cf7966f010927 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt new file mode 100644 index 0000000000000..0ba7432e6d898 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.5) +project(carla_sensor_kit_launch) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch + data + config +) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml new file mode 100644 index 0000000000000..5525f8189b213 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml @@ -0,0 +1,45 @@ +image_width: 1920 +image_height: 1080 +camera_name: traffic_light/camera +camera_matrix: + rows: 3 + cols: 3 + data: + [ + 2410.755261, + 0.000000, + 922.621401, + 0.000000, + 2403.573140, + 534.752500, + 0.000000, + 0.000000, + 1.000000, + ] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] +projection_matrix: + rows: 3 + cols: 4 + data: + [ + 2370.254883, + 0.000000, + 920.136018, + 0.000000, + 0.000000, + 2388.885254, + 535.599668, + 0.000000, + 0.000000, + 0.000000, + 1.000000, + 0.000000, + ] diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml new file mode 100644 index 0000000000000..a5381436ebbc4 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml new file mode 100644 index 0000000000000..472051f25de01 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000000..e41aeef657456 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -0,0 +1,110 @@ +# Copyright 2020 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def launch_setup(context, *args, **kwargs): + + # set concat filter as a component + concat_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="concatenate_data", + remappings=[ + ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), + ("output", "concatenated/pointcloud"), + ], + parameters=[ + { + "input_topics": [ + "/sensing/lidar/top/outlier_filtered/pointcloud", + "/sensing/lidar/left/outlier_filtered/pointcloud", + "/sensing/lidar/right/outlier_filtered/pointcloud", + ], + "output_frame": LaunchConfiguration("base_frame"), + "timeout_sec": 0.01, + "input_twist_topic_type": "twist", + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[], + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + + target_container = ( + container + if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else LaunchConfiguration("container_name") + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=target_container, + condition=IfCondition(LaunchConfiguration("use_concat_filter")), + ) + + return [container, concat_loader] + + +def generate_launch_description(): + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg("base_frame", "base_link") + add_launch_arg("use_multithread", "False") + add_launch_arg("use_intra_process", "False") + add_launch_arg("use_pointcloud_container", "False") + add_launch_arg("container_name", "pointcloud_preprocessor_container") + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)] + ) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml new file mode 100644 index 0000000000000..02cc9df228c29 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml new file mode 100644 index 0000000000000..1d2e1dece2c20 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml @@ -0,0 +1,26 @@ + + + + carla_sensor_kit_launch + 0.1.0 + The carla_sensor_kit_launch package + Hatem Darweesh + Apache License 2.0 + + ament_cmake_auto + + common_sensor_launch + gnss_poser + pointcloud_preprocessor + tamagawa_imu_driver + topic_tools + ublox_gps + usb_cam + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt new file mode 100644 index 0000000000000..76585c6207b3f --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 3.5) +project(common_carla_sensor_launch) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch +) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml new file mode 100644 index 0000000000000..4dff1789703e6 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py new file mode 100644 index 0000000000000..0b27efb5d7099 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py @@ -0,0 +1,208 @@ +# Copyright 2020 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode +import yaml + + +def get_vehicle_info(context): + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py + gp = context.launch_configurations.get("ros_params", {}) + if not gp: + gp = dict(context.launch_configurations.get("global_params", {})) + p = {} + p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] + p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] + p["min_longitudinal_offset"] = -gp["rear_overhang"] + p["max_longitudinal_offset"] = gp["front_overhang"] + gp["wheel_base"] + p["min_lateral_offset"] = -(gp["wheel_tread"] / 2.0 + gp["right_overhang"]) + p["max_lateral_offset"] = gp["wheel_tread"] / 2.0 + gp["left_overhang"] + p["min_height_offset"] = 0.0 + p["max_height_offset"] = gp["vehicle_height"] + return p + + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration("vehicle_mirror_param_file").perform(context) + with open(path, "r") as f: + p = yaml.safe_load(f)["/**"]["ros__parameters"] + return p + + +def launch_setup(context, *args, **kwargs): + def create_parameter_dict(*args): + result = {} + for x in args: + result[x] = LaunchConfiguration(x) + return result + + nodes = [] + + cropbox_parameters = create_parameter_dict("input_frame", "output_frame") + cropbox_parameters["negative"] = True + + vehicle_info = get_vehicle_info(context) + cropbox_parameters["min_x"] = vehicle_info["min_longitudinal_offset"] + cropbox_parameters["max_x"] = vehicle_info["max_longitudinal_offset"] + cropbox_parameters["min_y"] = vehicle_info["min_lateral_offset"] + cropbox_parameters["max_y"] = vehicle_info["max_lateral_offset"] + cropbox_parameters["min_z"] = vehicle_info["min_height_offset"] + cropbox_parameters["max_z"] = vehicle_info["max_height_offset"] + + nodes.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="crop_box_filter_self", + remappings=[ + ("input", "pointcloud_raw_ex"), + ("output", "self_cropped/pointcloud_ex"), + ], + parameters=[cropbox_parameters], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + ) + + mirror_info = get_vehicle_mirror_info(context) + cropbox_parameters["min_x"] = mirror_info["min_longitudinal_offset"] + cropbox_parameters["max_x"] = mirror_info["max_longitudinal_offset"] + cropbox_parameters["min_y"] = mirror_info["min_lateral_offset"] + cropbox_parameters["max_y"] = mirror_info["max_lateral_offset"] + cropbox_parameters["min_z"] = mirror_info["min_height_offset"] + cropbox_parameters["max_z"] = mirror_info["max_height_offset"] + + nodes.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="crop_box_filter_mirror", + remappings=[ + ("input", "self_cropped/pointcloud_ex"), + ("output", "mirror_cropped/pointcloud_ex"), + ], + parameters=[cropbox_parameters], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + ) + + nodes.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::RingOutlierFilterComponent", + name="ring_outlier_filter", + remappings=[ + ("input", "rectified/pointcloud_ex"), + ("output", "outlier_filtered/pointcloud"), + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + # need unique name, otherwise all processes in same container and the node names then clash + name="velodyne_node_container", + namespace="pointcloud_preprocessor", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=nodes, + ) + + distortion_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::DistortionCorrectorComponent", + name="distortion_corrector_node", + remappings=[ + ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), + ("~/input/imu", "/sensing/imu/imu_data"), + ("~/input/pointcloud", "mirror_cropped/pointcloud_ex"), + ("~/output/pointcloud", "rectified/pointcloud_ex"), + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + distortion_relay_component = ComposableNode( + package="topic_tools", + plugin="topic_tools::RelayNode", + name="pointcloud_distortion_relay", + namespace="", + parameters=[ + {"input_topic": "mirror_cropped/pointcloud_ex"}, + {"output_topic": "rectified/pointcloud_ex"} + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + # one way to add a ComposableNode conditional on a launch argument to a + # container. The `ComposableNode` itself doesn't accept a condition + distortion_loader = LoadComposableNodes( + composable_node_descriptions=[distortion_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration("use_distortion_corrector")), + ) + distortion_relay_loader = LoadComposableNodes( + composable_node_descriptions=[distortion_relay_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_distortion_corrector")), + ) + + return [container, distortion_loader, distortion_relay_loader] + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None, description=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append( + DeclareLaunchArgument(name, default_value=default_value, description=description) + ) + + add_launch_arg("base_frame", "base_link", "base frame id") + add_launch_arg("container_name", "velodyne_composable_node_container", "container name") + add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox") + add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox") + add_launch_arg( + "vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml" + ) + add_launch_arg("use_multithread", "False", "use multithread") + add_launch_arg("use_intra_process", "False", "use ROS2 component container communication") + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)] + ) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml new file mode 100644 index 0000000000000..c8028c196dc83 --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml @@ -0,0 +1,22 @@ + + + + common_carla_sensor_launch + 0.1.0 + The common_carla_sensor_launch package + Hatem Darweesh + Apache License 2.0 + + ament_cmake_auto + + velodyne_driver + velodyne_monitor + velodyne_pointcloud + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg b/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg new file mode 100644 index 0000000000000..5214751c7ba6b --- /dev/null +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg @@ -0,0 +1,15 @@ +[flake8] +# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_flake8/ament_flake8/configuration/ament_flake8.ini +extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,CNL100,E203,E501,Q000 +import-order-style = pep8 +max-line-length = 100 +show-source = true +statistics = true + +[isort] +profile=black +line_length=100 +force_sort_within_sections=true +force_single_line=true +reverse_relative=true +known_third_party=launch diff --git a/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt b/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt new file mode 100644 index 0000000000000..d83a30d877e08 --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt @@ -0,0 +1,69 @@ +cmake_minimum_required(VERSION 3.5) +project(pointcloud_interface) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) +endif() + + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + + +find_package(Boost COMPONENTS signals) +find_package(PCL REQUIRED COMPONENTS common) + + + +find_package(PkgConfig REQUIRED) +pkg_check_modules(YAML_CPP REQUIRED yaml-cpp) +find_path(YAML_CPP_INCLUDE_DIR + NAMES yaml_cpp.h + PATHS ${YAML_CPP_INCLUDE_DIRS}) +find_library(YAML_CPP_LIBRARY + NAMES YAML_CPP + PATHS ${YAML_CPP_LIBRARY_DIRS}) + +find_package(OpenCV REQUIRED) + +link_directories(${YAML_CPP_LIBRARY_DIRS}) + +if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") + add_definitions(-DHAVE_NEW_YAMLCPP) +endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") + +include_directories( + ${OpenCV_INCLUDE_DIRS} + ${PCL_COMMON_INCLUDE_DIRS} +) + +ament_auto_add_library(pointcloud_interface SHARED + src/pointcloud_interface/pointcloud_interface_node.cpp +) + + +# workaround to allow deprecated header to build on both galactic and rolling +if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) + target_compile_definitions(pointcloud_interface PRIVATE + USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER + ) +endif() + +rclcpp_components_register_node(pointcloud_interface + PLUGIN "PointCloudInterface" + EXECUTABLE pointcloud_interface_node +) + + +ament_auto_package( + INSTALL_TO_SHARE + launch +) + diff --git a/bridge/CARLA_Autoware/pointcloud_interface/README.md b/bridge/CARLA_Autoware/pointcloud_interface/README.md new file mode 100644 index 0000000000000..b292d1b6c1dcf --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/README.md @@ -0,0 +1,4 @@ +# carla_pointcloud_interface + +Convert Simple point cloud message to Autoware recognized Extended cloud message. + diff --git a/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp b/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp new file mode 100644 index 0000000000000..335a9ae4b46c3 --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp @@ -0,0 +1,31 @@ + +#ifndef MODEL_LOG_NODE_HPP_ +#define MODEL_LOG_NODE_HPP_ + +#include +#include +#include "rclcpp/rclcpp.hpp" +#include +#include +#include +#include + +class PointCloudInterface : public rclcpp::Node +{ +public: + explicit PointCloudInterface(const rclcpp::NodeOptions & node_options); + virtual ~PointCloudInterface(); + +private: + std::shared_ptr tf_buffer_; + rclcpp::Publisher::SharedPtr velodyne_points_raw; + rclcpp::Publisher::SharedPtr velodyne_points_top; + rclcpp::Publisher::SharedPtr velodyne_points_con; + std::shared_ptr tf_listener_; + rclcpp::Subscription::SharedPtr carla_cloud_; + std::string tf_output; + void processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg); + void setupTF(); +}; + +#endif \ No newline at end of file diff --git a/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml b/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml new file mode 100644 index 0000000000000..8b6eb39bba2dd --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml @@ -0,0 +1,3 @@ + + + diff --git a/bridge/CARLA_Autoware/pointcloud_interface/package.xml b/bridge/CARLA_Autoware/pointcloud_interface/package.xml new file mode 100644 index 0000000000000..0aec53de9c4a4 --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/package.xml @@ -0,0 +1,35 @@ + + + + pointcloud_interface + 1.0.0 + Convert CARLA 4D point cloud message to Autoware XYZIRADT cloud message + Muhammad Raditya Giovanni + Apache License 2.0 + + ament_cmake_auto + + angles + diagnostic_updater + autoware_auto_vehicle_msgs + autoware_auto_control_msgs + geometry_msgs + libpcl-all-dev + message_filters + pcl_ros + pcl_conversions + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_ros + velodyne_msgs + visualization_msgs + yaml-cpp + cv_bridge + image_transport + + + ament_cmake + + diff --git a/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp b/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp new file mode 100644 index 0000000000000..b56b1424e555c --- /dev/null +++ b/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp @@ -0,0 +1,55 @@ +#include "pointcloud_interface/pointcloud_interface_node.hpp" +#include +#include +#include +#include + + +void PointCloudInterface::processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg) +{ + { + sensor_msgs::msg::PointCloud2 transformed_cloud; + if (pcl_ros::transformPointCloud(tf_output, *scanMsg, transformed_cloud, *tf_buffer_)) + { + + transformed_cloud.header.stamp = scanMsg->header.stamp; + velodyne_points_top->publish(transformed_cloud); + velodyne_points_con->publish(transformed_cloud); + velodyne_points_raw->publish(transformed_cloud); + } + } + +} + +void PointCloudInterface::setupTF() +{ + tf_buffer_ = std::make_shared(this->get_clock()); + tf_listener_ = std::make_shared(*tf_buffer_); +} + +PointCloudInterface::~PointCloudInterface() +{ + +} + +PointCloudInterface::PointCloudInterface(const rclcpp::NodeOptions & node_options) +: Node("carla_pointcloud_interface_node", node_options), tf_output("base_link") +{ + + carla_cloud_ = + this->create_subscription( + "carla_pointcloud", rclcpp::SensorDataQoS(), + std::bind(&PointCloudInterface::processScan, this, std::placeholders::_1)); + { + setupTF(); + velodyne_points_raw = + this->create_publisher("/points_raw", rclcpp::SensorDataQoS()); + velodyne_points_top = + this->create_publisher("/sensing/lidar/top/outlier_filtered/pointcloud", rclcpp::SensorDataQoS()); + velodyne_points_con = + this->create_publisher("/sensing/lidar/concatenated/pointcloud", rclcpp::SensorDataQoS()); + } +} + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(PointCloudInterface) From 37008c186bdd6bc607f577f3eb283d0c02aa0f08 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 15 Mar 2024 05:15:50 +0000 Subject: [PATCH 02/50] style(pre-commit): autofix --- .../GNSS_Interface/CMakeLists.txt | 3 +- .../CARLA_Autoware/GNSS_Interface/README.md | 1 - .../gnss_interface/gnss_interface_node.hpp | 141 ++++++------ .../launch/gnss_interface.launch.xml | 2 - .../CARLA_Autoware/GNSS_Interface/package.xml | 12 +- .../gnss_interface/gnss_interface_node.cpp | 103 ++++----- bridge/CARLA_Autoware/README.md | 43 ++-- .../carla_autoware/config/objects.json | 217 +++++++++--------- .../launch/carla_autoware.launch.xml | 1 - .../launch/carla_ros.launch.xml | 89 ++++--- .../launch/e2e_simulator.launch.xml | 10 +- .../CARLA_Autoware/carla_autoware/package.xml | 35 ++- .../CARLA_Autoware/carla_autoware/setup.cfg | 2 +- bridge/CARLA_Autoware/carla_autoware/setup.py | 38 +-- .../src/carla_autoware/carla_autoware.py | 118 ++++++---- .../carla_sensor_kit_launch/README.md | 2 +- .../launch/imu.launch.xml | 4 +- .../launch/pointcloud_preprocessor.launch.py | 2 - .../launch/velodyne_node_container.launch.py | 6 +- .../pointcloud_interface/CMakeLists.txt | 3 +- .../pointcloud_interface/README.md | 1 - .../pointcloud_interface_node.hpp | 21 +- .../pointcloud_interface/package.xml | 14 +- .../pointcloud_interface_node.cpp | 54 ++--- 24 files changed, 471 insertions(+), 451 deletions(-) diff --git a/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt b/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt index a817198813e60..a5129ffb3d2c7 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt +++ b/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt @@ -26,7 +26,7 @@ ament_auto_add_library(gnss_interface SHARED target_link_libraries(gnss_interface ${PROJ_LIBRARIES}) -rclcpp_components_register_node(gnss_interface +rclcpp_components_register_node(gnss_interface PLUGIN "GnssInterface" EXECUTABLE gnss_interface_node ) @@ -35,4 +35,3 @@ ament_auto_package( INSTALL_TO_SHARE launch ) - diff --git a/bridge/CARLA_Autoware/GNSS_Interface/README.md b/bridge/CARLA_Autoware/GNSS_Interface/README.md index 356de168b8d13..b3d5a12fa8142 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/README.md +++ b/bridge/CARLA_Autoware/GNSS_Interface/README.md @@ -1,4 +1,3 @@ # gnss Interface Node Convert GNSS CARLA messages to pose and pose with covariance - diff --git a/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp b/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp index ec2c9f97b4caa..034af17d42a12 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp +++ b/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp @@ -1,105 +1,104 @@ -#ifndef GNSS_ -#define GNSS_ +#ifndef GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ +#define GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ -#include -#include -#include -#include #include "rclcpp/rclcpp.hpp" -#include + #include #include +#include + #include +#include + +#include +#include +#include class GnssInterface : public rclcpp::Node { public: - explicit GnssInterface(const rclcpp::NodeOptions & node_options); - virtual ~GnssInterface(); - std::string tf_output_frame_; - -private: + explicit GnssInterface(const rclcpp::NodeOptions & node_options); + virtual ~GnssInterface(); + std::string tf_output_frame_; +private: rclcpp::Subscription::SharedPtr sub_gnss_fix; rclcpp::Publisher::SharedPtr pup_pose; rclcpp::Publisher::SharedPtr pup_pose_with_cov; - void GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg); - }; -namespace interface { - namespace gnss { +namespace interface +{ +namespace gnss +{ class GPSPoint { public: - double x, y, z; - double lat, lon, alt; - double dir, a; - - GPSPoint() - { - x = y = z = 0; - lat = lon = alt = 0; - dir = a = 0; - } - - GPSPoint(const double& x, const double& y, const double& z, const double& a) - { - this->x = x; - this->y = y; - this->z = z; - this->a = a; - - lat = 0; - lon = 0; - alt = 0; - dir = 0; - } - - std::string ToString() - { - std::stringstream str; - str.precision(12); - str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; - str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; - return str.str(); - } + double x, y, z; + double lat, lon, alt; + double dir, a; + + GPSPoint() + { + x = y = z = 0; + lat = lon = alt = 0; + dir = a = 0; + } + + GPSPoint(const double & x, const double & y, const double & z, const double & a) + { + this->x = x; + this->y = y; + this->z = z; + this->a = a; + + lat = 0; + lon = 0; + alt = 0; + dir = 0; + } + + std::string ToString() + { + std::stringstream str; + str.precision(12); + str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; + str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; + return str.str(); + } }; - class WayPoint { public: - GPSPoint pos; - WayPoint() - { - } - - WayPoint(const double& x, const double& y, const double& z, const double& a) - { - pos.x = x; - pos.y = y; - pos.z = z; - pos.a = a; - } + GPSPoint pos; + WayPoint() {} + + WayPoint(const double & x, const double & y, const double & z, const double & a) + { + pos.x = x; + pos.y = y; + pos.z = z; + pos.a = a; + } }; -class MappingUtils { +class MappingUtils +{ public: - MappingUtils(); - virtual ~MappingUtils(); + MappingUtils(); + virtual ~MappingUtils(); - static void llaToxyz(const std::string& proj_str, const WayPoint& origin, const double& lat, - const double& lon, const double& alt, double& x_out, double& y_out, double& z_out); + static void llaToxyz( + const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon, + const double & alt, double & x_out, double & y_out, double & z_out); }; -} -} - -#endif - +} // namespace gnss +} // namespace interface +#endif // GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ diff --git a/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml b/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml index 5a14dbc2ed04b..556e94f2821b1 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml +++ b/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml @@ -9,6 +9,4 @@ - - diff --git a/bridge/CARLA_Autoware/GNSS_Interface/package.xml b/bridge/CARLA_Autoware/GNSS_Interface/package.xml index 0793b71f731bd..396359de45f38 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/package.xml +++ b/bridge/CARLA_Autoware/GNSS_Interface/package.xml @@ -12,17 +12,17 @@ autoware_cmake angles - diagnostic_updater - geometry_msgs - message_filters + diagnostic_updater + geometry_msgs + message_filters + proj rclcpp rclcpp_components sensor_msgs tf2 - tf2_ros + tf2_ros tinyxml - proj - + ament_cmake diff --git a/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp b/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp index d4d1a29a31eae..9b5543d458796 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp +++ b/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp @@ -1,84 +1,81 @@ #include "gnss_interface/gnss_interface_node.hpp" -#include +#include -namespace interface { - namespace gnss { +namespace interface +{ +namespace gnss +{ using namespace std; - -MappingUtils::MappingUtils() { +MappingUtils::MappingUtils() +{ } -MappingUtils::~MappingUtils() { +MappingUtils::~MappingUtils() +{ } +void MappingUtils::llaToxyz( + const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon, + const double & alt, double & x_out, double & y_out, double & z_out) +{ + if (proj_str.size() < 8) return; -void MappingUtils::llaToxyz(const std::string& proj_str, const WayPoint& origin, - const double& lat, const double& lon, const double& alt, - double& x_out, double& y_out, double& z_out) { - if (proj_str.size() < 8) return; - - PJ_CONTEXT *C = proj_context_create(); - PJ *P = proj_create_crs_to_crs(C, "EPSG:4326", proj_str.c_str(), NULL); + PJ_CONTEXT * C = proj_context_create(); + PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", proj_str.c_str(), NULL); - if (P == 0) return; + if (P == 0) return; - PJ_COORD gps_degrees = proj_coord(lat, lon, alt, 0); - PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); - x_out = xyz_out.enu.e + origin.pos.x; - y_out = xyz_out.enu.n + origin.pos.y; - z_out = xyz_out.enu.u + origin.pos.z; + PJ_COORD gps_degrees = proj_coord(lat, lon, alt, 0); + PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); + x_out = xyz_out.enu.e + origin.pos.x; + y_out = xyz_out.enu.n + origin.pos.y; + z_out = xyz_out.enu.u + origin.pos.z; - proj_destroy(P); - proj_context_destroy(C); + proj_destroy(P); + proj_context_destroy(C); } -} -} - +} // namespace gnss +} // namespace interface void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg) { - geometry_msgs::msg::PoseStamped pose_; - geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; - interface::gnss::WayPoint origin, p; - interface::gnss::MappingUtils::llaToxyz( - "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs", - origin, msg->latitude, msg->longitude, msg->altitude, - p.pos.x, p.pos.y, p.pos.z); - pose_.header = msg->header; - pose_.header.frame_id = "map"; - pose_.pose.position.x = p.pos.x; - pose_.pose.position.y = p.pos.y; - pose_.pose.position.z = p.pos.z; - - pose_cov_.header = pose_.header; - pose_cov_.pose.pose = pose_.pose; - - pup_pose->publish(pose_); - pup_pose_with_cov->publish(pose_cov_); - + geometry_msgs::msg::PoseStamped pose_; + geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; + interface::gnss::WayPoint origin, p; + interface::gnss::MappingUtils::llaToxyz( + "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs", origin, + msg->latitude, msg->longitude, msg->altitude, p.pos.x, p.pos.y, p.pos.z); + pose_.header = msg->header; + pose_.header.frame_id = "map"; + pose_.pose.position.x = p.pos.x; + pose_.pose.position.y = p.pos.y; + pose_.pose.position.z = p.pos.z; + + pose_cov_.header = pose_.header; + pose_cov_.pose.pose = pose_.pose; + + pup_pose->publish(pose_); + pup_pose_with_cov->publish(pose_cov_); } GnssInterface::~GnssInterface() { - } GnssInterface::GnssInterface(const rclcpp::NodeOptions & node_options) : Node("gnss_interface_node", node_options), tf_output_frame_("base_link") { - sub_gnss_fix = this->create_subscription( - "carla/ego_vehicle/gnss", 1, - std::bind(&GnssInterface::GnssCallBack, this, std::placeholders::_1)); - - pup_pose = this->create_publisher( - "/sensing/gnss/pose", 1); - pup_pose_with_cov = this->create_publisher( - "/sensing/gnss/pose_with_covariance", 1); -} + sub_gnss_fix = this->create_subscription( + "carla/ego_vehicle/gnss", 1, + std::bind(&GnssInterface::GnssCallBack, this, std::placeholders::_1)); + pup_pose = this->create_publisher("/sensing/gnss/pose", 1); + pup_pose_with_cov = this->create_publisher( + "/sensing/gnss/pose_with_covariance", 1); +} #include "rclcpp_components/register_node_macro.hpp" RCLCPP_COMPONENTS_REGISTER_NODE(GnssInterface) diff --git a/bridge/CARLA_Autoware/README.md b/bridge/CARLA_Autoware/README.md index 4d616e4f6723f..cbf6f4e75f2b0 100644 --- a/bridge/CARLA_Autoware/README.md +++ b/bridge/CARLA_Autoware/README.md @@ -1,48 +1,58 @@ # CARLA_Autoware + # ROS2/Autoware.universe bridge for CARLA simulator +### Thanks to for ROS2 Humble support for CARLA ROS bridge + +This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). ( for ROS2 Humble) -### Thanks to https://github.com/gezp for ROS2 Humble support for CARLA ROS bridge. - This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). (https://github.com/gezp for ROS2 Humble) -- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.14-ubuntu-22.04). +- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.14-ubuntu-22.04). - Add the egg file to the folder: ../CARLA_0.9.14/PythonAPI/carla/dist - And install the wheel using pip. -# Environment -|ubuntu|ros|carla|autoware| -|:---:|:---:|:---:|:---:| -|22.04|humble|0.9.14|universe/master| +# Environment + +| ubuntu | ros | carla | autoware | +| :----: | :----: | :----: | :-------------: | +| 22.04 | humble | 0.9.14 | universe/master | # Setup + ## install -* [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) -* [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) -* [autoware containts](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) + +- [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) +- [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) +- [autoware containts](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) - 3. Create ``map_projector_info.yaml`` and add ``projector_type: local`` on the first line. -* Clone this repositories and ROSBridge + 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. +- Clone this repositories and ROSBridge + ``` git clone https://github.com/mraditya01/CARLA_Autoware.git git clone --recurse-submodules https://github.com/gezp/carla_ros.git -b humble-carla-0.9.14 ``` - * Copy the files (sensor_kit_calibration.yaml, sensors.calibration.yaml) from folder "GNSS_interface/src/carla_sensor_kit_launch/carla_sensor_kit_description/config" to "src/param/autoware_individual_params/carla_sensor_kit". +- Copy the files (sensor_kit_calibration.yaml, sensors.calibration.yaml) from folder "GNSS_interface/src/carla_sensor_kit_launch/carla_sensor_kit_description/config" to "src/param/autoware_individual_params/carla_sensor_kit". ## build + ```bash cd colcon_ws colcon build --symlink-install ``` # Run + 1. Run carla, change map, spawn object if you need + ```bash cd CARLA ./CarlaUE4.sh -prefernvidia -quality-level=Low ``` 2. Run ros nodes + ```bash ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit ``` @@ -53,6 +63,7 @@ ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map 6. Engage # Tips -* If you want to edit the sensors configuration used in CARLA, edit ``objects.json`` located in ``carla_autoware/config``. -* You will also need to edit the ``carla_sensor_kit_description`` if you change the sensor configuration. -* Misalignment might occurs during initialization, pressing ``init by gnss`` button should fix it. \ No newline at end of file + +- If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. +- You will also need to edit the `carla_sensor_kit_description` if you change the sensor configuration. +- Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. diff --git a/bridge/CARLA_Autoware/carla_autoware/config/objects.json b/bridge/CARLA_Autoware/carla_autoware/config/objects.json index ff458c22276db..ac6b39666ec5f 100644 --- a/bridge/CARLA_Autoware/carla_autoware/config/objects.json +++ b/bridge/CARLA_Autoware/carla_autoware/config/objects.json @@ -1,118 +1,125 @@ -{ - "objects": - [ +{ + "objects": [ + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" + }, + { + "type": "vehicle.toyota.prius", + "id": "ego_vehicle", + "sensors": [ { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" + "type": "sensor.camera.rgb", + "id": "rgb_front", + "spawn_point": { "x": 0.7, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, + "image_size_x": 1280, + "image_size_y": 720, + "fov": 100.0 }, { - "type": "sensor.pseudo.objects", - "id": "objects" + "type": "sensor.camera.rgb", + "id": "rgb_view", + "spawn_point": { "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0 }, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "attached_objects": [ + { + "type": "actor.pseudo.control", + "id": "control" + } + ] }, { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" + "type": "sensor.lidar.ray_cast", + "id": "lidar", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 2.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "noise_stddev": 0.0 }, { - "type": "sensor.pseudo.markers", - "id": "markers" + "type": "sensor.opendrive_map", + "id": "OpenDRIVE", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0 } }, + { - "type": "sensor.pseudo.opendrive_map", - "id": "map" + "type": "sensor.other.gnss", + "id": "gnss", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6 }, + "noise_alt_stddev": 0.0, + "noise_lat_stddev": 0.0, + "noise_lon_stddev": 0.0, + "noise_alt_bias": 0.0, + "noise_lat_bias": 0.0, + "noise_lon_bias": 0.0 }, { - "type": "vehicle.toyota.prius", - "id": "ego_vehicle", - "sensors": - [ - { - "type": "sensor.camera.rgb", - "id": "rgb_front", - "spawn_point": {"x": 0.7, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "image_size_x": 1280, - "image_size_y": 720, - "fov": 100.0 - }, - { - "type": "sensor.camera.rgb", - "id": "rgb_view", - "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0}, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "attached_objects": - [ - { - "type": "actor.pseudo.control", - "id": "control" - } - ] - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "noise_stddev": 0.0 - }, - { - "type": "sensor.opendrive_map", - "id": "OpenDRIVE", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0} - }, - - { - "type": "sensor.other.gnss", - "id": "gnss", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6}, - "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0, - "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0 - }, - { - "type": "sensor.other.imu", - "id": "imu", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0, - "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0, - "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 - }, - { - "type": "sensor.other.collision", - "id": "collision", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} - }, - { - "type": "sensor.other.lane_invasion", - "id": "lane_invasion", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} - }, - { - "type": "sensor.pseudo.tf", - "id": "tf" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.odom", - "id": "odometry" - }, - { - "type": "sensor.pseudo.speedometer", - "id": "speedometer" - }, - { - "type": "actor.pseudo.control", - "id": "control" - } - ] + "type": "sensor.other.imu", + "id": "imu", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, + "noise_accel_stddev_x": 0.0, + "noise_accel_stddev_y": 0.0, + "noise_accel_stddev_z": 0.0, + "noise_gyro_stddev_x": 0.0, + "noise_gyro_stddev_y": 0.0, + "noise_gyro_stddev_z": 0.0, + "noise_gyro_bias_x": 0.0, + "noise_gyro_bias_y": 0.0, + "noise_gyro_bias_z": 0.0 + }, + { + "type": "sensor.other.collision", + "id": "collision", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 0.0 } + }, + { + "type": "sensor.other.lane_invasion", + "id": "lane_invasion", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 0.0 } + }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "actor.pseudo.control", + "id": "control" } - ] + ] + } + ] } diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml index b84bdd889d53e..6e82013a84531 100644 --- a/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml +++ b/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml @@ -8,4 +8,3 @@ - diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml index 46bdd4bb86cd4..a3b1b892b68fb 100644 --- a/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml +++ b/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml @@ -1,52 +1,49 @@ - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + - + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml b/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml index 345054570bde7..8226a45c29088 100644 --- a/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml +++ b/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml @@ -32,22 +32,18 @@ - + - - - - - + + - diff --git a/bridge/CARLA_Autoware/carla_autoware/package.xml b/bridge/CARLA_Autoware/carla_autoware/package.xml index 10b5b5b6101be..2d50f4742f2eb 100644 --- a/bridge/CARLA_Autoware/carla_autoware/package.xml +++ b/bridge/CARLA_Autoware/carla_autoware/package.xml @@ -6,40 +6,33 @@ CARLA Simulator Team MIT - std_msgs + ros2launch ros_compatibility - geometry_msgs - tf2 - tf2_ros - sensor_msgs - sensor_msgs_py - - nav_msgs - carla_msgs - autoware_auto_vehicle_msgs + std_msgs + astuff_sensor_msgs autoware_auto_control_msgs - rclpy - numpy - datetime + autoware_auto_vehicle_msgs carla_data_provider - astuff_sensor_msgs - - + carla_msgs + datetime + geometry_msgs math + nav_msgs + numpy + rclpy + sensor_msgs + sensor_msgs_py + tf2 + tf2_ros transform3d - - ros2launch ament_cmake ament_lint_auto ament_lint_common - - - ament_python diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.cfg b/bridge/CARLA_Autoware/carla_autoware/setup.cfg index 5cb120ba598b4..6ca2d4bdad9a1 100644 --- a/bridge/CARLA_Autoware/carla_autoware/setup.cfg +++ b/bridge/CARLA_Autoware/carla_autoware/setup.cfg @@ -1,4 +1,4 @@ [develop] script_dir=$base/lib/carla_autoware [install] -install_scripts=$base/lib/carla_autoware \ No newline at end of file +install_scripts=$base/lib/carla_autoware diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.py b/bridge/CARLA_Autoware/carla_autoware/setup.py index f0e39dcba107c..c02295fdd714b 100644 --- a/bridge/CARLA_Autoware/carla_autoware/setup.py +++ b/bridge/CARLA_Autoware/carla_autoware/setup.py @@ -1,44 +1,44 @@ - - """ Setup for carla_manual_control """ -import os from glob import glob -ROS_VERSION = int(os.environ['ROS_VERSION']) +import os + +ROS_VERSION = int(os.environ["ROS_VERSION"]) if ROS_VERSION == 1: from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup - d = generate_distutils_setup(packages=['carla_autoware'], package_dir={'': 'src'}) + d = generate_distutils_setup(packages=["carla_autoware"], package_dir={"": "src"}) setup(**d) elif ROS_VERSION == 2: from setuptools import setup - package_name = 'carla_autoware' + package_name = "carla_autoware" setup( name=package_name, - version='0.0.0', + version="0.0.0", packages=[package_name], data_files=[ - ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - ('share/' + package_name, glob('config/*.json')), - ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name), glob('launch/*.launch.xml')) + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), + ("share/" + package_name, glob("config/*.json")), + ("share/" + package_name, ["package.xml"]), + (os.path.join("share", package_name), glob("launch/*.launch.xml")), ], - install_requires=['setuptools'], + install_requires=["setuptools"], zip_safe=True, - maintainer='mradityagio', - maintainer_email='mradityagio@gmail.com', - description='CARLA ROS2 bridge for AUTOWARE', - license='MIT', - tests_require=['pytest'], + maintainer="mradityagio", + maintainer_email="mradityagio@gmail.com", + description="CARLA ROS2 bridge for AUTOWARE", + license="MIT", + tests_require=["pytest"], entry_points={ - 'console_scripts': ['carla_autoware = carla_autoware.carla_autoware:main'], + "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], }, - package_dir={'': 'src'}, + package_dir={"": "src"}, ) diff --git a/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py index 471d0248318ef..41aab41397860 100644 --- a/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -1,56 +1,84 @@ -import rclpy -from rclpy.node import Node -from autoware_auto_vehicle_msgs.msg import VelocityReport, SteeringReport, ControlModeReport, GearReport -from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleControl +import math +import threading + from autoware_auto_control_msgs.msg import AckermannControlCommand -from sensor_msgs.msg import Imu, PointCloud2 +from autoware_auto_vehicle_msgs.msg import ControlModeReport +from autoware_auto_vehicle_msgs.msg import GearReport +from autoware_auto_vehicle_msgs.msg import SteeringReport +from autoware_auto_vehicle_msgs.msg import VelocityReport import carla +from carla_msgs.msg import CarlaEgoVehicleControl +from carla_msgs.msg import CarlaEgoVehicleStatus +import rclpy +from rclpy.node import Node from rclpy.qos import QoSProfile -import math -from transforms3d.euler import quat2euler +from sensor_msgs.msg import Imu +from sensor_msgs.msg import PointCloud2 from sensor_msgs_py.point_cloud2 import create_cloud -import threading +from transforms3d.euler import quat2euler class CarlaVehicleInterface(Node): def __init__(self): rclpy.init(args=None) - super().__init__('carla_vehicle_interface_node') - + super().__init__("carla_vehicle_interface_node") + client = carla.Client("localhost", 2000) - client.set_timeout(20) - - self._world = client.get_world() + client.set_timeout(20) + + self._world = client.get_world() self.current_vel = 0.0 self.target_vel = 0.0 self.vel_diff = 0.0 self.current_control = carla.VehicleControl() self.ros2_node = rclpy.create_node("carla_autoware") - + self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) self.spin_thread.start() - + # Publishes Topics used for AUTOWARE - self.pub_vel_state = self.ros2_node.create_publisher(VelocityReport, '/vehicle/status/velocity_status', 1) - self.pub_steering_state = self.ros2_node.create_publisher(SteeringReport, '/vehicle/status/steering_status', 1) - self.pub_ctrl_mode = self.ros2_node.create_publisher(ControlModeReport, '/vehicle/status/control_mode', 1) - self.pub_gear_state = self.ros2_node.create_publisher(GearReport, '/vehicle/status/gear_status', 1) - self.pub_control = self.ros2_node.create_publisher(CarlaEgoVehicleControl, '/carla/ego_vehicle/vehicle_control_cmd', 1) - self.vehicle_imu_publisher = self.ros2_node.create_publisher(Imu, '/sensing/imu/tamagawa/imu_raw', 1) - self.sensing_cloud_publisher = self.ros2_node.create_publisher(PointCloud2, '/carla_pointcloud', 1) + self.pub_vel_state = self.ros2_node.create_publisher( + VelocityReport, "/vehicle/status/velocity_status", 1 + ) + self.pub_steering_state = self.ros2_node.create_publisher( + SteeringReport, "/vehicle/status/steering_status", 1 + ) + self.pub_ctrl_mode = self.ros2_node.create_publisher( + ControlModeReport, "/vehicle/status/control_mode", 1 + ) + self.pub_gear_state = self.ros2_node.create_publisher( + GearReport, "/vehicle/status/gear_status", 1 + ) + self.pub_control = self.ros2_node.create_publisher( + CarlaEgoVehicleControl, "/carla/ego_vehicle/vehicle_control_cmd", 1 + ) + self.vehicle_imu_publisher = self.ros2_node.create_publisher( + Imu, "/sensing/imu/tamagawa/imu_raw", 1 + ) + self.sensing_cloud_publisher = self.ros2_node.create_publisher( + PointCloud2, "/carla_pointcloud", 1 + ) # Subscribe Topics used in Control - self.sub_status = self.ros2_node.create_subscription(CarlaEgoVehicleStatus, '/carla/ego_vehicle/vehicle_status', self.ego_status_callback, 1) - self.sub_control = self.ros2_node.create_subscription(AckermannControlCommand, '/control/command/control_cmd', self.control_callback, qos_profile=QoSProfile(depth=1)) - self.sub_imu = self.ros2_node.create_subscription(Imu, '/carla/ego_vehicle/imu', self.publish_imu, 1) - self.sub_lidar = self.ros2_node.create_subscription(PointCloud2, '/carla/ego_vehicle/lidar', self.publish_lidar, qos_profile=QoSProfile(depth=1)) - - - - - - + self.sub_status = self.ros2_node.create_subscription( + CarlaEgoVehicleStatus, "/carla/ego_vehicle/vehicle_status", self.ego_status_callback, 1 + ) + self.sub_control = self.ros2_node.create_subscription( + AckermannControlCommand, + "/control/command/control_cmd", + self.control_callback, + qos_profile=QoSProfile(depth=1), + ) + self.sub_imu = self.ros2_node.create_subscription( + Imu, "/carla/ego_vehicle/imu", self.publish_imu, 1 + ) + self.sub_lidar = self.ros2_node.create_subscription( + PointCloud2, + "/carla/ego_vehicle/lidar", + self.publish_lidar, + qos_profile=QoSProfile(depth=1), + ) def ego_status_callback(self, in_status): """ @@ -62,18 +90,17 @@ def ego_status_callback(self, in_status): out_gear_state = GearReport() out_vel_state.header = in_status.header - out_vel_state.header.frame_id = 'base_link' + out_vel_state.header.frame_id = "base_link" out_vel_state.longitudinal_velocity = in_status.velocity out_vel_state.lateral_velocity = 0.0 out_vel_state.heading_rate = 0.0 self.current_vel = in_status.velocity - out_steering_state.stamp = in_status.header.stamp - out_steering_state.steering_tire_angle = (-in_status.control.steer) + out_steering_state.steering_tire_angle = -in_status.control.steer out_gear_state.stamp = in_status.header.stamp - out_gear_state.report = GearReport.DRIVE + out_gear_state.report = GearReport.DRIVE out_ctrl_mode.stamp = in_status.header.stamp out_ctrl_mode.mode = ControlModeReport.AUTONOMOUS @@ -82,7 +109,7 @@ def ego_status_callback(self, in_status): self.pub_steering_state.publish(out_steering_state) self.pub_ctrl_mode.publish(out_ctrl_mode) self.pub_gear_state.publish(out_gear_state) - + def control_callback(self, in_cmd): """ Callback function for CARLA Control @@ -103,7 +130,7 @@ def control_callback(self, in_cmd): else: out_cmd.brake = 0.01 - out_cmd.steer = (-in_cmd.lateral.steering_tire_angle) + out_cmd.steer = -in_cmd.lateral.steering_tire_angle self.pub_control.publish(out_cmd) def publish_lidar(self, lidar_msg): @@ -111,24 +138,25 @@ def publish_lidar(self, lidar_msg): Publish LIDAR to Interface """ lidar_msg.header.frame_id = "velodyne_top" - self.sensing_cloud_publisher.publish(lidar_msg) - + self.sensing_cloud_publisher.publish(lidar_msg) + def publish_imu(self, imu_msg): """ Publish IMU to Autoware - """ + """ imu_msg.header.frame_id = "tamagawa/imu_link" self.vehicle_imu_publisher.publish(imu_msg) - + def publish_gnss(self, msg): """ Publish GNSS to Autoware """ self.publisher_map.publish(msg) - + def main(args=None): carla_vehicle_interface = CarlaVehicleInterface() -if __name__ == '__main__': - main() \ No newline at end of file + +if __name__ == "__main__": + main() diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md index 856700225f228..db5f83d412201 100644 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md @@ -1,3 +1,3 @@ # carla_sensor_kit_launch -A sensor kit configurations for CARLA Simulator +A sensor kit configurations for CARLA Simulator diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml index a5381436ebbc4..0cb769d8fdd44 100644 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml @@ -3,12 +3,12 @@ - + - + diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py index e41aeef657456..11634a22736b0 100644 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -26,7 +26,6 @@ def launch_setup(context, *args, **kwargs): - # set concat filter as a component concat_component = ComposableNode( package="pointcloud_preprocessor", @@ -79,7 +78,6 @@ def launch_setup(context, *args, **kwargs): def generate_launch_description(): - launch_arguments = [] def add_launch_arg(name: str, default_value=None): diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py index 0b27efb5d7099..f3186d4db43db 100644 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py +++ b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py @@ -149,7 +149,7 @@ def create_parameter_dict(*args): namespace="", parameters=[ {"input_topic": "mirror_cropped/pointcloud_ex"}, - {"output_topic": "rectified/pointcloud_ex"} + {"output_topic": "rectified/pointcloud_ex"}, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -164,7 +164,9 @@ def create_parameter_dict(*args): distortion_relay_loader = LoadComposableNodes( composable_node_descriptions=[distortion_relay_component], target_container=container, - condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_distortion_corrector")), + condition=launch.conditions.UnlessCondition( + LaunchConfiguration("use_distortion_corrector") + ), ) return [container, distortion_loader, distortion_relay_loader] diff --git a/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt b/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt index d83a30d877e08..2ecfd1ee9aa26 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt +++ b/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt @@ -56,7 +56,7 @@ if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) ) endif() -rclcpp_components_register_node(pointcloud_interface +rclcpp_components_register_node(pointcloud_interface PLUGIN "PointCloudInterface" EXECUTABLE pointcloud_interface_node ) @@ -66,4 +66,3 @@ ament_auto_package( INSTALL_TO_SHARE launch ) - diff --git a/bridge/CARLA_Autoware/pointcloud_interface/README.md b/bridge/CARLA_Autoware/pointcloud_interface/README.md index b292d1b6c1dcf..f04e4c0dd7216 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/README.md +++ b/bridge/CARLA_Autoware/pointcloud_interface/README.md @@ -1,4 +1,3 @@ # carla_pointcloud_interface Convert Simple point cloud message to Autoware recognized Extended cloud message. - diff --git a/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp b/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp index 335a9ae4b46c3..d88e971e6635c 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp +++ b/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp @@ -1,21 +1,24 @@ -#ifndef MODEL_LOG_NODE_HPP_ -#define MODEL_LOG_NODE_HPP_ +#ifndef POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ +#define POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ -#include -#include #include "rclcpp/rclcpp.hpp" -#include + #include + +#include #include #include +#include +#include + class PointCloudInterface : public rclcpp::Node { public: - explicit PointCloudInterface(const rclcpp::NodeOptions & node_options); - virtual ~PointCloudInterface(); - + explicit PointCloudInterface(const rclcpp::NodeOptions & node_options); + virtual ~PointCloudInterface(); + private: std::shared_ptr tf_buffer_; rclcpp::Publisher::SharedPtr velodyne_points_raw; @@ -28,4 +31,4 @@ class PointCloudInterface : public rclcpp::Node void setupTF(); }; -#endif \ No newline at end of file +#endif // POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ diff --git a/bridge/CARLA_Autoware/pointcloud_interface/package.xml b/bridge/CARLA_Autoware/pointcloud_interface/package.xml index 0aec53de9c4a4..e95d83b4ff3f2 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/package.xml +++ b/bridge/CARLA_Autoware/pointcloud_interface/package.xml @@ -3,21 +3,23 @@ pointcloud_interface 1.0.0 - Convert CARLA 4D point cloud message to Autoware XYZIRADT cloud message + Convert CARLA 4D point cloud message to Autoware XYZIRADT cloud message Muhammad Raditya Giovanni Apache License 2.0 ament_cmake_auto angles - diagnostic_updater - autoware_auto_vehicle_msgs autoware_auto_control_msgs + autoware_auto_vehicle_msgs + cv_bridge + diagnostic_updater geometry_msgs + image_transport libpcl-all-dev message_filters - pcl_ros pcl_conversions + pcl_ros rclcpp rclcpp_components sensor_msgs @@ -26,9 +28,7 @@ velodyne_msgs visualization_msgs yaml-cpp - cv_bridge - image_transport - + ament_cmake diff --git a/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp b/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp index b56b1424e555c..1540d4c2773ca 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp +++ b/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp @@ -1,24 +1,23 @@ #include "pointcloud_interface/pointcloud_interface_node.hpp" + +#include + #include #include -#include -#include +#include void PointCloudInterface::processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg) { - { - sensor_msgs::msg::PointCloud2 transformed_cloud; - if (pcl_ros::transformPointCloud(tf_output, *scanMsg, transformed_cloud, *tf_buffer_)) - { - - transformed_cloud.header.stamp = scanMsg->header.stamp; - velodyne_points_top->publish(transformed_cloud); - velodyne_points_con->publish(transformed_cloud); - velodyne_points_raw->publish(transformed_cloud); - } - } - + { + sensor_msgs::msg::PointCloud2 transformed_cloud; + if (pcl_ros::transformPointCloud(tf_output, *scanMsg, transformed_cloud, *tf_buffer_)) { + transformed_cloud.header.stamp = scanMsg->header.stamp; + velodyne_points_top->publish(transformed_cloud); + velodyne_points_con->publish(transformed_cloud); + velodyne_points_raw->publish(transformed_cloud); + } + } } void PointCloudInterface::setupTF() @@ -29,26 +28,23 @@ void PointCloudInterface::setupTF() PointCloudInterface::~PointCloudInterface() { - } PointCloudInterface::PointCloudInterface(const rclcpp::NodeOptions & node_options) : Node("carla_pointcloud_interface_node", node_options), tf_output("base_link") { - - carla_cloud_ = - this->create_subscription( - "carla_pointcloud", rclcpp::SensorDataQoS(), - std::bind(&PointCloudInterface::processScan, this, std::placeholders::_1)); - { - setupTF(); - velodyne_points_raw = - this->create_publisher("/points_raw", rclcpp::SensorDataQoS()); - velodyne_points_top = - this->create_publisher("/sensing/lidar/top/outlier_filtered/pointcloud", rclcpp::SensorDataQoS()); - velodyne_points_con = - this->create_publisher("/sensing/lidar/concatenated/pointcloud", rclcpp::SensorDataQoS()); - } + carla_cloud_ = this->create_subscription( + "carla_pointcloud", rclcpp::SensorDataQoS(), + std::bind(&PointCloudInterface::processScan, this, std::placeholders::_1)); + { + setupTF(); + velodyne_points_raw = + this->create_publisher("/points_raw", rclcpp::SensorDataQoS()); + velodyne_points_top = this->create_publisher( + "/sensing/lidar/top/outlier_filtered/pointcloud", rclcpp::SensorDataQoS()); + velodyne_points_con = this->create_publisher( + "/sensing/lidar/concatenated/pointcloud", rclcpp::SensorDataQoS()); + } } #include "rclcpp_components/register_node_macro.hpp" From fc2893796aa64c9677d899a151a541c2eb4705f9 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 15 Mar 2024 16:11:21 +0900 Subject: [PATCH 03/50] minor fixes --- .../CARLA_Autoware/GNSS_Interface/README.md | 3 - .../launch/gnss_interface.launch.xml | 12 - bridge/CARLA_Autoware/LICENSE | 21 -- .../.markdown-link-check.json | 13 -- .../.markdownlint.yaml | 9 - .../.pre-commit-config-optional.yaml | 6 - .../.pre-commit-config.yaml | 68 ------ .../carla_sensor_kit_launch/.prettierignore | 2 - .../carla_sensor_kit_launch/.prettierrc.yaml | 20 -- .../carla_sensor_kit_launch/.yamllint.yaml | 23 -- .../CODE_OF_CONDUCT.md | 132 ----------- .../carla_sensor_kit_launch/CONTRIBUTING.md | 3 - .../carla_sensor_kit_launch/DISCLAIMER.md | 46 ---- .../carla_sensor_kit_launch/LICENSE | 201 ----------------- .../carla_sensor_kit_launch/NOTICE | 8 - .../carla_sensor_kit_launch/README.md | 3 - .../build_depends.repos | 9 - .../CMakeLists.txt | 11 - .../config/sensor_kit_calibration.yaml | 92 -------- .../config/sensors_calibration.yaml | 15 -- .../carla_sensor_kit_description/package.xml | 17 -- .../urdf/sensor_kit.xacro | 209 ----------------- .../urdf/sensors.xacro | 30 --- .../carla_sensor_kit_launch/CMakeLists.txt | 16 -- .../sensor_kit.param.yaml | 0 .../data/traffic_light_camera.yaml | 45 ---- .../launch/imu.launch.xml | 14 -- .../launch/lidar.launch.xml | 43 ---- .../launch/pointcloud_preprocessor.launch.py | 108 --------- .../launch/sensing.launch.xml | 33 --- .../carla_sensor_kit_launch/package.xml | 26 --- .../common_carla_sensor_launch/CMakeLists.txt | 14 -- .../launch/velodyne_lidar.launch.xml | 12 - .../launch/velodyne_node_container.launch.py | 210 ------------------ .../common_carla_sensor_launch/package.xml | 22 -- .../carla_sensor_kit_launch/setup.cfg | 15 -- .../pointcloud_interface/README.md | 3 - .../launch/pointcloud_interface.xml | 3 - .../carla_autoware/CMakeLists.txt | 0 .../CARLA_Autoware/carla_autoware}/README.md | 0 .../carla_autoware/config/objects.json | 0 .../launch/carla_autoware.launch.xml | 4 +- .../launch/carla_ros.launch.xml | 0 .../launch/e2e_simulator.launch.xml | 0 .../CARLA_Autoware/carla_autoware/package.xml | 2 - .../carla_autoware/resource/carla_autoware | 0 .../CARLA_Autoware/carla_autoware/setup.cfg | 0 .../CARLA_Autoware/carla_autoware/setup.py | 3 - .../src/carla_autoware/carla_autoware.py | 25 +-- .../carla_gnss_interface}/CMakeLists.txt | 12 +- .../carla_gnss_interface/README.md | 7 + .../carla_gnss_interface_node.hpp | 7 +- .../launch/gnss_interface.launch.xml | 5 + .../carla_gnss_interface}/package.xml | 2 +- .../carla_gnss_interface_node.cpp | 6 +- .../CMakeLists.txt | 12 +- .../carla_pointcloud_interface/README.md | 11 + .../carla_pointcloud_interface_node.hpp | 8 +- .../launch/carla_pointcloud_interface.xml | 3 + .../carla_pointcloud_interface}/package.xml | 2 +- .../carla_pointcloud_interface_node.cpp | 4 +- 61 files changed, 63 insertions(+), 1567 deletions(-) delete mode 100644 bridge/CARLA_Autoware/GNSS_Interface/README.md delete mode 100644 bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml delete mode 100644 bridge/CARLA_Autoware/LICENSE delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml delete mode 100644 bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg delete mode 100644 bridge/CARLA_Autoware/pointcloud_interface/README.md delete mode 100644 bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml rename {bridge => simulator}/CARLA_Autoware/carla_autoware/CMakeLists.txt (100%) rename {bridge/CARLA_Autoware => simulator/CARLA_Autoware/carla_autoware}/README.md (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/config/objects.json (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml (69%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/package.xml (99%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/resource/carla_autoware (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/setup.cfg (100%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/setup.py (96%) rename {bridge => simulator}/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py (91%) rename {bridge/CARLA_Autoware/GNSS_Interface => simulator/CARLA_Autoware/carla_gnss_interface}/CMakeLists.txt (67%) create mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/README.md rename bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp => simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp (90%) create mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml rename {bridge/CARLA_Autoware/GNSS_Interface => simulator/CARLA_Autoware/carla_gnss_interface}/package.xml (96%) rename bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp => simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp (96%) rename {bridge/CARLA_Autoware/pointcloud_interface => simulator/CARLA_Autoware/carla_pointcloud_interface}/CMakeLists.txt (80%) create mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/README.md rename bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp => simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp (77%) create mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml rename {bridge/CARLA_Autoware/pointcloud_interface => simulator/CARLA_Autoware/carla_pointcloud_interface}/package.xml (96%) rename bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp => simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp (94%) diff --git a/bridge/CARLA_Autoware/GNSS_Interface/README.md b/bridge/CARLA_Autoware/GNSS_Interface/README.md deleted file mode 100644 index b3d5a12fa8142..0000000000000 --- a/bridge/CARLA_Autoware/GNSS_Interface/README.md +++ /dev/null @@ -1,3 +0,0 @@ -# gnss Interface Node - -Convert GNSS CARLA messages to pose and pose with covariance diff --git a/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml b/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml deleted file mode 100644 index 556e94f2821b1..0000000000000 --- a/bridge/CARLA_Autoware/GNSS_Interface/launch/gnss_interface.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/LICENSE b/bridge/CARLA_Autoware/LICENSE deleted file mode 100644 index b3c8c7e3fc138..0000000000000 --- a/bridge/CARLA_Autoware/LICENSE +++ /dev/null @@ -1,21 +0,0 @@ -MIT License - -Copyright (c) 2024 Giovanni Muhammad Raditya - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json deleted file mode 100644 index dec3db1ad1c8d..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdown-link-check.json +++ /dev/null @@ -1,13 +0,0 @@ -{ - "aliveStatusCodes": [200, 206, 403], - "ignorePatterns": [ - { - "pattern": "^http://localhost" - }, - { - "pattern": "^https://github.com/.*/discussions/new" - } - ], - "retryOn429": true, - "retryCount": 10 -} diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml deleted file mode 100644 index df1f518dc0d48..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.markdownlint.yaml +++ /dev/null @@ -1,9 +0,0 @@ -# See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. -default: true -MD013: false -MD024: - siblings_only: true -MD033: false -MD041: false -MD046: false -MD049: false diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml deleted file mode 100644 index a805f1201c414..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config-optional.yaml +++ /dev/null @@ -1,6 +0,0 @@ -repos: - - repo: https://github.com/tcort/markdown-link-check - rev: v3.10.0 - hooks: - - id: markdown-link-check - args: [--config=.markdown-link-check.json] diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml deleted file mode 100644 index 46b8247bde927..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.pre-commit-config.yaml +++ /dev/null @@ -1,68 +0,0 @@ -ci: - autofix_commit_msg: "ci(pre-commit): autofix" - autoupdate_commit_msg: "ci(pre-commit): autoupdate" - -repos: - - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.3.0 - hooks: - - id: check-json - - id: check-merge-conflict - - id: check-toml - - id: check-xml - - id: check-yaml - - id: detect-private-key - - id: end-of-file-fixer - - id: mixed-line-ending - - id: trailing-whitespace - args: [--markdown-linebreak-ext=md] - - - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.31.1 - hooks: - - id: markdownlint - args: [-c, .markdownlint.yaml, --fix] - - - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.7.1 - hooks: - - id: prettier - - - repo: https://github.com/adrienverge/yamllint - rev: v1.26.3 - hooks: - - id: yamllint - - - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.7.1 - hooks: - - id: flake8-ros - - id: prettier-xacro - - id: prettier-launch-xml - - id: prettier-package-xml - - id: ros-include-guard - - id: sort-package-xml - - - repo: https://github.com/shellcheck-py/shellcheck-py - rev: v0.8.0.4 - hooks: - - id: shellcheck - - - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.5.1-1 - hooks: - - id: shfmt - args: [-w, -s, -i=4] - - - repo: https://github.com/pycqa/isort - rev: 5.10.1 - hooks: - - id: isort - - - repo: https://github.com/psf/black - rev: 22.6.0 - hooks: - - id: black - args: [--line-length=100] - -exclude: .svg diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore deleted file mode 100644 index a3c34d00a1377..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierignore +++ /dev/null @@ -1,2 +0,0 @@ -*.param.yaml -*.rviz diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml deleted file mode 100644 index e29bf32762769..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.prettierrc.yaml +++ /dev/null @@ -1,20 +0,0 @@ -printWidth: 100 -tabWidth: 2 -overrides: - - files: package.xml - options: - printWidth: 1000 - xmlSelfClosingSpace: false - xmlWhitespaceSensitivity: ignore - - - files: "*.launch.xml" - options: - printWidth: 200 - xmlSelfClosingSpace: false - xmlWhitespaceSensitivity: ignore - - - files: "*.xacro" - options: - printWidth: 200 - xmlSelfClosingSpace: false - xmlWhitespaceSensitivity: ignore diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml deleted file mode 100644 index 6228c70f02da9..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/.yamllint.yaml +++ /dev/null @@ -1,23 +0,0 @@ -extends: default - -ignore: | - .clang-tidy - *.param.yaml - -rules: - braces: - level: error - max-spaces-inside: 1 # To format with Prettier - comments: - level: error - min-spaces-from-content: 1 # To be compatible with C++ and Python - document-start: - level: error - present: false # Don't need document start markers - line-length: disable # Delegate to Prettier - truthy: - level: error - check-keys: false # To allow 'on' of GitHub Actions - quoted-strings: - level: error - required: only-when-needed # To keep consistent style diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md deleted file mode 100644 index c493cad4da591..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CODE_OF_CONDUCT.md +++ /dev/null @@ -1,132 +0,0 @@ -# Contributor Covenant Code of Conduct - -## Our Pledge - -We as members, contributors, and leaders pledge to make participation in our -community a harassment-free experience for everyone, regardless of age, body -size, visible or invisible disability, ethnicity, sex characteristics, gender -identity and expression, level of experience, education, socio-economic status, -nationality, personal appearance, race, caste, color, religion, or sexual -identity and orientation. - -We pledge to act and interact in ways that contribute to an open, welcoming, -diverse, inclusive, and healthy community. - -## Our Standards - -Examples of behavior that contributes to a positive environment for our -community include: - -- Demonstrating empathy and kindness toward other people -- Being respectful of differing opinions, viewpoints, and experiences -- Giving and gracefully accepting constructive feedback -- Accepting responsibility and apologizing to those affected by our mistakes, - and learning from the experience -- Focusing on what is best not just for us as individuals, but for the overall - community - -Examples of unacceptable behavior include: - -- The use of sexualized language or imagery, and sexual attention or advances of - any kind -- Trolling, insulting or derogatory comments, and personal or political attacks -- Public or private harassment -- Publishing others' private information, such as a physical or email address, - without their explicit permission -- Other conduct which could reasonably be considered inappropriate in a - professional setting - -## Enforcement Responsibilities - -Community leaders are responsible for clarifying and enforcing our standards of -acceptable behavior and will take appropriate and fair corrective action in -response to any behavior that they deem inappropriate, threatening, offensive, -or harmful. - -Community leaders have the right and responsibility to remove, edit, or reject -comments, commits, code, wiki edits, issues, and other contributions that are -not aligned to this Code of Conduct, and will communicate reasons for moderation -decisions when appropriate. - -## Scope - -This Code of Conduct applies within all community spaces, and also applies when -an individual is officially representing the community in public spaces. -Examples of representing our community include using an official e-mail address, -posting via an official social media account, or acting as an appointed -representative at an online or offline event. - -## Enforcement - -Instances of abusive, harassing, or otherwise unacceptable behavior may be -reported to the community leaders responsible for enforcement at -conduct@autoware.org. -All complaints will be reviewed and investigated promptly and fairly. - -All community leaders are obligated to respect the privacy and security of the -reporter of any incident. - -## Enforcement Guidelines - -Community leaders will follow these Community Impact Guidelines in determining -the consequences for any action they deem in violation of this Code of Conduct: - -### 1. Correction - -**Community Impact**: Use of inappropriate language or other behavior deemed -unprofessional or unwelcome in the community. - -**Consequence**: A private, written warning from community leaders, providing -clarity around the nature of the violation and an explanation of why the -behavior was inappropriate. A public apology may be requested. - -### 2. Warning - -**Community Impact**: A violation through a single incident or series of -actions. - -**Consequence**: A warning with consequences for continued behavior. No -interaction with the people involved, including unsolicited interaction with -those enforcing the Code of Conduct, for a specified period of time. This -includes avoiding interactions in community spaces as well as external channels -like social media. Violating these terms may lead to a temporary or permanent -ban. - -### 3. Temporary Ban - -**Community Impact**: A serious violation of community standards, including -sustained inappropriate behavior. - -**Consequence**: A temporary ban from any sort of interaction or public -communication with the community for a specified period of time. No public or -private interaction with the people involved, including unsolicited interaction -with those enforcing the Code of Conduct, is allowed during this period. -Violating these terms may lead to a permanent ban. - -### 4. Permanent Ban - -**Community Impact**: Demonstrating a pattern of violation of community -standards, including sustained inappropriate behavior, harassment of an -individual, or aggression toward or disparagement of classes of individuals. - -**Consequence**: A permanent ban from any sort of public interaction within the -community. - -## Attribution - -This Code of Conduct is adapted from the [Contributor Covenant][homepage], -version 2.1, available at -[https://www.contributor-covenant.org/version/2/1/code_of_conduct.html][v2.1]. - -Community Impact Guidelines were inspired by -[Mozilla's code of conduct enforcement ladder][mozilla coc]. - -For answers to common questions about this code of conduct, see the FAQ at -[https://www.contributor-covenant.org/faq][faq]. Translations are available at -[https://www.contributor-covenant.org/translations][translations]. - -[homepage]: https://www.contributor-covenant.org -[v2.1]: https://www.contributor-covenant.org/version/2/1/code_of_conduct.html -[mozilla coc]: https://github.com/mozilla/diversity -[faq]: https://www.contributor-covenant.org/faq -[translations]: https://www.contributor-covenant.org/translations diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md deleted file mode 100644 index 22c7ee28e8d9a..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/CONTRIBUTING.md +++ /dev/null @@ -1,3 +0,0 @@ -# Contributing - -See . diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md deleted file mode 100644 index 1b5a9bbe4d981..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/DISCLAIMER.md +++ /dev/null @@ -1,46 +0,0 @@ -DISCLAIMER - -“Autoware” will be provided by The Autoware Foundation under the Apache License 2.0. -This “DISCLAIMER” will be applied to all users of Autoware (a “User” or “Users”) with -the Apache License 2.0 and Users shall hereby approve and acknowledge all the contents -specified in this disclaimer below and will be deemed to consent to this -disclaimer without any objection upon utilizing or downloading Autoware. - -Disclaimer and Waiver of Warranties - -1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, - EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) - including but not limited to any representation or warranty (i) of fitness or - suitability for a particular purpose contemplated by the Users, (ii) of the - expected functions, commercial value, accuracy, or usefulness of the Service, - (iii) that the use by the Users of the Service complies with the laws and - regulations applicable to the Users or any internal rules established by - industrial organizations, (iv) that the Service will be free of interruption or - defects, (v) of the non-infringement of any third party's right and (vi) the - accuracy of the content of the Services and the software itself. - -2. The Autoware Foundation shall not be liable for any damage incurred by the - User that are attributable to the Autoware Foundation for any reasons - whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR - INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. - -3. A User shall be entirely responsible for the content posted by the User and - its use of any content of the Service or the Website. If the User is held - responsible in a civil action such as a claim for damages or even in a criminal - case, the Autoware Foundation and member companies, governments and academic & - non-profit organizations and their directors, officers, employees and agents - (collectively, the “Indemnified Parties”) shall be completely discharged from - any rights or assertions the User may have against the Indemnified Parties, or - from any legal action, litigation or similar procedures. - -Indemnity - -A User shall indemnify and hold the Indemnified Parties harmless from any of -their damages, losses, liabilities, costs or expenses (including attorneys' -fees or criminal compensation), or any claims or demands made against the -Indemnified Parties by any third party, due to or arising out of, or in -connection with utilizing Autoware (including the representations and -warranties), the violation of applicable Product Liability Law of each country -(including criminal case) or violation of any applicable laws by the Users, or -the content posted by the User or its use of any content of the Service or the -Website. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE b/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE deleted file mode 100644 index 261eeb9e9f8b2..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/LICENSE +++ /dev/null @@ -1,201 +0,0 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE b/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE deleted file mode 100644 index 60fbbe96174e5..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/NOTICE +++ /dev/null @@ -1,8 +0,0 @@ -carla_sensor_kit_launch -Copyright 2021 The Autoware Foundation - -This product includes software developed at -The Autoware Foundation (https://www.autoware.org/). - -This product includes code developed by TIER IV. -Copyright 2020 TIER IV, Inc. diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md b/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md deleted file mode 100644 index db5f83d412201..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/README.md +++ /dev/null @@ -1,3 +0,0 @@ -# carla_sensor_kit_launch - -A sensor kit configurations for CARLA Simulator diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos b/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos deleted file mode 100644 index 08e78b602a8d0..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/build_depends.repos +++ /dev/null @@ -1,9 +0,0 @@ -repositories: - autoware_common: - type: git - url: https://github.com/autowarefoundation/autoware_common.git - version: main - sensor_component_description: - type: git - url: https://github.com/tier4/sensor_component_description.git - version: main diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt deleted file mode 100644 index b2b320a645d80..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(carla_sensor_kit_description) - -find_package(ament_cmake_auto REQUIRED) - -ament_auto_find_build_dependencies() - -ament_auto_package(INSTALL_TO_SHARE - urdf - config -) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml deleted file mode 100644 index aa2aeb5b3a42e..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensor_kit_calibration.yaml +++ /dev/null @@ -1,92 +0,0 @@ -sensor_kit_base_link: - camera0/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - camera1/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - camera2/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - camera3/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - camera4/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - camera5/camera_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - traffic_light_right_camera/camera_link: - x: -0.7 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - traffic_light_left_camera/camera_link: - x: 0.7 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - velodyne_top_base_link: - x: 0.0 - y: 0.0 - z: 1.0 - roll: 0.0 - pitch: 0.0 - yaw: 0 - velodyne_left_base_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - velodyne_right_base_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - gnss_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - tamagawa/imu_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml deleted file mode 100644 index c25cc52357e97..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/config/sensors_calibration.yaml +++ /dev/null @@ -1,15 +0,0 @@ -base_link: - sensor_kit_base_link: - x: 0.0 - y: 0.0 - z: 1.6 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 - velodyne_rear_base_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml deleted file mode 100644 index 638e73fb15972..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - carla_sensor_kit_description - 0.1.0 - The carla_sensor_kit_description package - Hatem Darweesh - Apache License 2.0 - - ament_cmake_auto - - velodyne_description - - - ament_cmake - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro deleted file mode 100644 index c40b383563186..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensor_kit.xacro +++ /dev/null @@ -1,209 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro deleted file mode 100644 index cf7966f010927..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_description/urdf/sensors.xacro +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt deleted file mode 100644 index 0ba7432e6d898..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(carla_sensor_kit_launch) - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package(INSTALL_TO_SHARE - launch - data - config -) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/config/diagnostic_aggregator/sensor_kit.param.yaml deleted file mode 100644 index e69de29bb2d1d..0000000000000 diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml deleted file mode 100644 index 5525f8189b213..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/data/traffic_light_camera.yaml +++ /dev/null @@ -1,45 +0,0 @@ -image_width: 1920 -image_height: 1080 -camera_name: traffic_light/camera -camera_matrix: - rows: 3 - cols: 3 - data: - [ - 2410.755261, - 0.000000, - 922.621401, - 0.000000, - 2403.573140, - 534.752500, - 0.000000, - 0.000000, - 1.000000, - ] -distortion_model: plumb_bob -distortion_coefficients: - rows: 1 - cols: 5 - data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] -rectification_matrix: - rows: 3 - cols: 3 - data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] -projection_matrix: - rows: 3 - cols: 4 - data: - [ - 2370.254883, - 0.000000, - 920.136018, - 0.000000, - 0.000000, - 2388.885254, - 535.599668, - 0.000000, - 0.000000, - 0.000000, - 1.000000, - 0.000000, - ] diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml deleted file mode 100644 index 0cb769d8fdd44..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/imu.launch.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml deleted file mode 100644 index 472051f25de01..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/lidar.launch.xml +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py deleted file mode 100644 index 11634a22736b0..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,108 +0,0 @@ -# Copyright 2020 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def launch_setup(context, *args, **kwargs): - # set concat filter as a component - concat_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="concatenate_data", - remappings=[ - ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), - ("output", "concatenated/pointcloud"), - ], - parameters=[ - { - "input_topics": [ - "/sensing/lidar/top/outlier_filtered/pointcloud", - "/sensing/lidar/left/outlier_filtered/pointcloud", - "/sensing/lidar/right/outlier_filtered/pointcloud", - ], - "output_frame": LaunchConfiguration("base_frame"), - "timeout_sec": 0.01, - "input_twist_topic_type": "twist", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[], - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("container_name") - ) - - # load concat or passthrough filter - concat_loader = LoadComposableNodes( - composable_node_descriptions=[concat_component], - target_container=target_container, - condition=IfCondition(LaunchConfiguration("use_concat_filter")), - ) - - return [container, concat_loader] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg("base_frame", "base_link") - add_launch_arg("use_multithread", "False") - add_launch_arg("use_intra_process", "False") - add_launch_arg("use_pointcloud_container", "False") - add_launch_arg("container_name", "pointcloud_preprocessor_container") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [set_container_executable, set_container_mt_executable] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml deleted file mode 100644 index 02cc9df228c29..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/launch/sensing.launch.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml deleted file mode 100644 index 1d2e1dece2c20..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/carla_sensor_kit_launch/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - carla_sensor_kit_launch - 0.1.0 - The carla_sensor_kit_launch package - Hatem Darweesh - Apache License 2.0 - - ament_cmake_auto - - common_sensor_launch - gnss_poser - pointcloud_preprocessor - tamagawa_imu_driver - topic_tools - ublox_gps - usb_cam - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt deleted file mode 100644 index 76585c6207b3f..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(common_carla_sensor_launch) - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package(INSTALL_TO_SHARE - launch -) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml deleted file mode 100644 index 4dff1789703e6..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_lidar.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py deleted file mode 100644 index f3186d4db43db..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/launch/velodyne_node_container.launch.py +++ /dev/null @@ -1,210 +0,0 @@ -# Copyright 2020 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -def get_vehicle_info(context): - # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support - # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py - gp = context.launch_configurations.get("ros_params", {}) - if not gp: - gp = dict(context.launch_configurations.get("global_params", {})) - p = {} - p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] - p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] - p["min_longitudinal_offset"] = -gp["rear_overhang"] - p["max_longitudinal_offset"] = gp["front_overhang"] + gp["wheel_base"] - p["min_lateral_offset"] = -(gp["wheel_tread"] / 2.0 + gp["right_overhang"]) - p["max_lateral_offset"] = gp["wheel_tread"] / 2.0 + gp["left_overhang"] - p["min_height_offset"] = 0.0 - p["max_height_offset"] = gp["vehicle_height"] - return p - - -def get_vehicle_mirror_info(context): - path = LaunchConfiguration("vehicle_mirror_param_file").perform(context) - with open(path, "r") as f: - p = yaml.safe_load(f)["/**"]["ros__parameters"] - return p - - -def launch_setup(context, *args, **kwargs): - def create_parameter_dict(*args): - result = {} - for x in args: - result[x] = LaunchConfiguration(x) - return result - - nodes = [] - - cropbox_parameters = create_parameter_dict("input_frame", "output_frame") - cropbox_parameters["negative"] = True - - vehicle_info = get_vehicle_info(context) - cropbox_parameters["min_x"] = vehicle_info["min_longitudinal_offset"] - cropbox_parameters["max_x"] = vehicle_info["max_longitudinal_offset"] - cropbox_parameters["min_y"] = vehicle_info["min_lateral_offset"] - cropbox_parameters["max_y"] = vehicle_info["max_lateral_offset"] - cropbox_parameters["min_z"] = vehicle_info["min_height_offset"] - cropbox_parameters["max_z"] = vehicle_info["max_height_offset"] - - nodes.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="crop_box_filter_self", - remappings=[ - ("input", "pointcloud_raw_ex"), - ("output", "self_cropped/pointcloud_ex"), - ], - parameters=[cropbox_parameters], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - ) - - mirror_info = get_vehicle_mirror_info(context) - cropbox_parameters["min_x"] = mirror_info["min_longitudinal_offset"] - cropbox_parameters["max_x"] = mirror_info["max_longitudinal_offset"] - cropbox_parameters["min_y"] = mirror_info["min_lateral_offset"] - cropbox_parameters["max_y"] = mirror_info["max_lateral_offset"] - cropbox_parameters["min_z"] = mirror_info["min_height_offset"] - cropbox_parameters["max_z"] = mirror_info["max_height_offset"] - - nodes.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="crop_box_filter_mirror", - remappings=[ - ("input", "self_cropped/pointcloud_ex"), - ("output", "mirror_cropped/pointcloud_ex"), - ], - parameters=[cropbox_parameters], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - ) - - nodes.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::RingOutlierFilterComponent", - name="ring_outlier_filter", - remappings=[ - ("input", "rectified/pointcloud_ex"), - ("output", "outlier_filtered/pointcloud"), - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - # need unique name, otherwise all processes in same container and the node names then clash - name="velodyne_node_container", - namespace="pointcloud_preprocessor", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=nodes, - ) - - distortion_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DistortionCorrectorComponent", - name="distortion_corrector_node", - remappings=[ - ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), - ("~/input/imu", "/sensing/imu/imu_data"), - ("~/input/pointcloud", "mirror_cropped/pointcloud_ex"), - ("~/output/pointcloud", "rectified/pointcloud_ex"), - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - distortion_relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="pointcloud_distortion_relay", - namespace="", - parameters=[ - {"input_topic": "mirror_cropped/pointcloud_ex"}, - {"output_topic": "rectified/pointcloud_ex"}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # one way to add a ComposableNode conditional on a launch argument to a - # container. The `ComposableNode` itself doesn't accept a condition - distortion_loader = LoadComposableNodes( - composable_node_descriptions=[distortion_component], - target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration("use_distortion_corrector")), - ) - distortion_relay_loader = LoadComposableNodes( - composable_node_descriptions=[distortion_relay_component], - target_container=container, - condition=launch.conditions.UnlessCondition( - LaunchConfiguration("use_distortion_corrector") - ), - ) - - return [container, distortion_loader, distortion_relay_loader] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - add_launch_arg("base_frame", "base_link", "base frame id") - add_launch_arg("container_name", "velodyne_composable_node_container", "container name") - add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox") - add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox") - add_launch_arg( - "vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml" - ) - add_launch_arg("use_multithread", "False", "use multithread") - add_launch_arg("use_intra_process", "False", "use ROS2 component container communication") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [set_container_executable, set_container_mt_executable] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml b/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml deleted file mode 100644 index c8028c196dc83..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/common_carla_sensor_launch/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - common_carla_sensor_launch - 0.1.0 - The common_carla_sensor_launch package - Hatem Darweesh - Apache License 2.0 - - ament_cmake_auto - - velodyne_driver - velodyne_monitor - velodyne_pointcloud - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg b/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg deleted file mode 100644 index 5214751c7ba6b..0000000000000 --- a/bridge/CARLA_Autoware/carla_sensor_kit_launch/setup.cfg +++ /dev/null @@ -1,15 +0,0 @@ -[flake8] -# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_flake8/ament_flake8/configuration/ament_flake8.ini -extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,CNL100,E203,E501,Q000 -import-order-style = pep8 -max-line-length = 100 -show-source = true -statistics = true - -[isort] -profile=black -line_length=100 -force_sort_within_sections=true -force_single_line=true -reverse_relative=true -known_third_party=launch diff --git a/bridge/CARLA_Autoware/pointcloud_interface/README.md b/bridge/CARLA_Autoware/pointcloud_interface/README.md deleted file mode 100644 index f04e4c0dd7216..0000000000000 --- a/bridge/CARLA_Autoware/pointcloud_interface/README.md +++ /dev/null @@ -1,3 +0,0 @@ -# carla_pointcloud_interface - -Convert Simple point cloud message to Autoware recognized Extended cloud message. diff --git a/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml b/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml deleted file mode 100644 index 8b6eb39bba2dd..0000000000000 --- a/bridge/CARLA_Autoware/pointcloud_interface/launch/pointcloud_interface.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt b/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/CMakeLists.txt rename to simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt diff --git a/bridge/CARLA_Autoware/README.md b/simulator/CARLA_Autoware/carla_autoware/README.md similarity index 100% rename from bridge/CARLA_Autoware/README.md rename to simulator/CARLA_Autoware/carla_autoware/README.md diff --git a/bridge/CARLA_Autoware/carla_autoware/config/objects.json b/simulator/CARLA_Autoware/carla_autoware/config/objects.json similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/config/objects.json rename to simulator/CARLA_Autoware/carla_autoware/config/objects.json diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml similarity index 69% rename from bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml rename to simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml index 6e82013a84531..1e71edcd8eb39 100644 --- a/bridge/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml @@ -4,7 +4,7 @@ - - + + diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml rename to simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml diff --git a/bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml rename to simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml diff --git a/bridge/CARLA_Autoware/carla_autoware/package.xml b/simulator/CARLA_Autoware/carla_autoware/package.xml similarity index 99% rename from bridge/CARLA_Autoware/carla_autoware/package.xml rename to simulator/CARLA_Autoware/carla_autoware/package.xml index 2d50f4742f2eb..4cad00c7420fa 100644 --- a/bridge/CARLA_Autoware/carla_autoware/package.xml +++ b/simulator/CARLA_Autoware/carla_autoware/package.xml @@ -26,8 +26,6 @@ tf2_ros transform3d - - ament_cmake ament_lint_auto diff --git a/bridge/CARLA_Autoware/carla_autoware/resource/carla_autoware b/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/resource/carla_autoware rename to simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.cfg b/simulator/CARLA_Autoware/carla_autoware/setup.cfg similarity index 100% rename from bridge/CARLA_Autoware/carla_autoware/setup.cfg rename to simulator/CARLA_Autoware/carla_autoware/setup.cfg diff --git a/bridge/CARLA_Autoware/carla_autoware/setup.py b/simulator/CARLA_Autoware/carla_autoware/setup.py similarity index 96% rename from bridge/CARLA_Autoware/carla_autoware/setup.py rename to simulator/CARLA_Autoware/carla_autoware/setup.py index c02295fdd714b..139f98586afc6 100644 --- a/bridge/CARLA_Autoware/carla_autoware/setup.py +++ b/simulator/CARLA_Autoware/carla_autoware/setup.py @@ -1,6 +1,3 @@ -""" -Setup for carla_manual_control -""" from glob import glob import os diff --git a/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py similarity index 91% rename from bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py rename to simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py index 41aab41397860..6b00e37c67e86 100644 --- a/bridge/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -1,4 +1,3 @@ -import math import threading from autoware_auto_control_msgs.msg import AckermannControlCommand @@ -14,8 +13,6 @@ from rclpy.qos import QoSProfile from sensor_msgs.msg import Imu from sensor_msgs.msg import PointCloud2 -from sensor_msgs_py.point_cloud2 import create_cloud -from transforms3d.euler import quat2euler class CarlaVehicleInterface(Node): @@ -81,9 +78,7 @@ def __init__(self): ) def ego_status_callback(self, in_status): - """ - Callback function for CARLA Ego Vehicle Status to AUTOWARE - """ + """Convert and publish CARLA Ego Vehicle Status to AUTOWARE.""" out_vel_state = VelocityReport() out_steering_state = SteeringReport() out_ctrl_mode = ControlModeReport() @@ -111,9 +106,7 @@ def ego_status_callback(self, in_status): self.pub_gear_state.publish(out_gear_state) def control_callback(self, in_cmd): - """ - Callback function for CARLA Control - """ + """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" out_cmd = CarlaEgoVehicleControl() self.target_vel = abs(in_cmd.longitudinal.speed) self.vel_diff = self.target_vel - self.current_vel @@ -134,28 +127,22 @@ def control_callback(self, in_cmd): self.pub_control.publish(out_cmd) def publish_lidar(self, lidar_msg): - """ - Publish LIDAR to Interface - """ + """Publish LIDAR to Interface.""" lidar_msg.header.frame_id = "velodyne_top" self.sensing_cloud_publisher.publish(lidar_msg) def publish_imu(self, imu_msg): - """ - Publish IMU to Autoware - """ + """Publish IMU to Autoware.""" imu_msg.header.frame_id = "tamagawa/imu_link" self.vehicle_imu_publisher.publish(imu_msg) def publish_gnss(self, msg): - """ - Publish GNSS to Autoware - """ + """Publish GNSS to Autoware.""" self.publisher_map.publish(msg) def main(args=None): - carla_vehicle_interface = CarlaVehicleInterface() + CarlaVehicleInterface() if __name__ == "__main__": diff --git a/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt similarity index 67% rename from bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt rename to simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt index a5129ffb3d2c7..75d8490890e4c 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(gnss_interface) +project(carla_gnss_interface) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() @@ -20,15 +20,15 @@ ament_auto_find_build_dependencies() find_package(PkgConfig REQUIRED) pkg_check_modules(PROJ REQUIRED proj) -ament_auto_add_library(gnss_interface SHARED - src/gnss_interface/gnss_interface_node.cpp +ament_auto_add_library(carla_gnss_interface SHARED + src/carla_gnss_interface/carla_gnss_interface_node.cpp ) -target_link_libraries(gnss_interface ${PROJ_LIBRARIES}) +target_link_libraries(carla_gnss_interface ${PROJ_LIBRARIES}) -rclcpp_components_register_node(gnss_interface +rclcpp_components_register_node(carla_gnss_interface PLUGIN "GnssInterface" - EXECUTABLE gnss_interface_node + EXECUTABLE carla_gnss_interface_node ) ament_auto_package( diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/README.md b/simulator/CARLA_Autoware/carla_gnss_interface/README.md new file mode 100644 index 0000000000000..8e3ec20befe68 --- /dev/null +++ b/simulator/CARLA_Autoware/carla_gnss_interface/README.md @@ -0,0 +1,7 @@ +# gnss Interface Node + +Convert GNSS CARLA messages to pose and pose with covariance + +1. Receive GNSS Messages: Subscribe to the GNSS messages published by CARLA `carla/ego_vehicle/gnss`. These messages typically include latitude, longitude, and altitude. + +2. Convert to ROS Pose and Pose with Covariance: Extract the position components (latitude, longitude, altitude) from the GNSS messages and create a ROS geometry_msgs/Pose and geometry_msgs/PoseWithCovariance message. Set the position fields (x, y, z) of the ROS Pose message by converting the corresponding latitude, longitude, and altitude values using proj. diff --git a/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp similarity index 90% rename from bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp rename to simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index 034af17d42a12..fec3c7c909dd8 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/include/gnss_interface/gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -1,6 +1,7 @@ +// Copyright 2024 Raditya. -#ifndef GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ -#define GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ +#ifndef CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ +#define CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ #include "rclcpp/rclcpp.hpp" @@ -101,4 +102,4 @@ class MappingUtils } // namespace gnss } // namespace interface -#endif // GNSS_INTERFACE__GNSS_INTERFACE_NODE_HPP_ +#endif // CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml b/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml new file mode 100644 index 0000000000000..6faf90f770022 --- /dev/null +++ b/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml @@ -0,0 +1,5 @@ + + + + + diff --git a/bridge/CARLA_Autoware/GNSS_Interface/package.xml b/simulator/CARLA_Autoware/carla_gnss_interface/package.xml similarity index 96% rename from bridge/CARLA_Autoware/GNSS_Interface/package.xml rename to simulator/CARLA_Autoware/carla_gnss_interface/package.xml index 396359de45f38..74aeac6e9c643 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/package.xml +++ b/simulator/CARLA_Autoware/carla_gnss_interface/package.xml @@ -1,7 +1,7 @@ - gnss_interface + carla_gnss_interface 1.0.0 Convert GNSS CARLA messages to pose and pose with covariance Muhammad Raditya Giovanni diff --git a/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp similarity index 96% rename from bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp rename to simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 9b5543d458796..0496371a66be9 100644 --- a/bridge/CARLA_Autoware/GNSS_Interface/src/gnss_interface/gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -1,4 +1,6 @@ -#include "gnss_interface/gnss_interface_node.hpp" +// Copyright 2024 Raditya. + +#include "carla_gnss_interface/carla_gnss_interface_node.hpp" #include @@ -7,8 +9,6 @@ namespace interface namespace gnss { -using namespace std; - MappingUtils::MappingUtils() { } diff --git a/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt similarity index 80% rename from bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt rename to simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt index 2ecfd1ee9aa26..43f49410ed151 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(pointcloud_interface) +project(carla_pointcloud_interface) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() @@ -44,21 +44,21 @@ include_directories( ${PCL_COMMON_INCLUDE_DIRS} ) -ament_auto_add_library(pointcloud_interface SHARED - src/pointcloud_interface/pointcloud_interface_node.cpp +ament_auto_add_library(carla_pointcloud_interface SHARED + src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp ) # workaround to allow deprecated header to build on both galactic and rolling if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) - target_compile_definitions(pointcloud_interface PRIVATE + target_compile_definitions(carla_pointcloud_interface PRIVATE USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER ) endif() -rclcpp_components_register_node(pointcloud_interface +rclcpp_components_register_node(carla_pointcloud_interface PLUGIN "PointCloudInterface" - EXECUTABLE pointcloud_interface_node + EXECUTABLE carla_pointcloud_interface_node ) diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md b/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md new file mode 100644 index 0000000000000..c47a171bfc415 --- /dev/null +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md @@ -0,0 +1,11 @@ +# carla_pointcloud_interface + +Relaying subscribed message from CARLA to Autoware related LIDAR topic message. + +Message Subscribed: +`carla_pointcloud` + +Message Published: +`/points_raw` +`/sensing/lidar/top/outlier_filtered/pointcloud` +`/sensing/lidar/concatenated/pointcloud` diff --git a/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp similarity index 77% rename from bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp rename to simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp index d88e971e6635c..75be0b56e9dbe 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/include/pointcloud_interface/pointcloud_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp @@ -1,6 +1,7 @@ +// Copyright 2024 Raditya. -#ifndef POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ -#define POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ +#ifndef CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ +#define CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ #include "rclcpp/rclcpp.hpp" @@ -10,6 +11,7 @@ #include #include +#include #include #include @@ -31,4 +33,4 @@ class PointCloudInterface : public rclcpp::Node void setupTF(); }; -#endif // POINTCLOUD_INTERFACE__POINTCLOUD_INTERFACE_NODE_HPP_ +#endif // CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml b/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml new file mode 100644 index 0000000000000..2b53ad1b2a50b --- /dev/null +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml @@ -0,0 +1,3 @@ + + + diff --git a/bridge/CARLA_Autoware/pointcloud_interface/package.xml b/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml similarity index 96% rename from bridge/CARLA_Autoware/pointcloud_interface/package.xml rename to simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml index e95d83b4ff3f2..5272a666d9ee0 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/package.xml +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml @@ -1,7 +1,7 @@ - pointcloud_interface + carla_pointcloud_interface 1.0.0 Convert CARLA 4D point cloud message to Autoware XYZIRADT cloud message Muhammad Raditya Giovanni diff --git a/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp similarity index 94% rename from bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp rename to simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp index 1540d4c2773ca..b3981d9bfc3f8 100644 --- a/bridge/CARLA_Autoware/pointcloud_interface/src/pointcloud_interface/pointcloud_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp @@ -1,4 +1,6 @@ -#include "pointcloud_interface/pointcloud_interface_node.hpp" +// Copyright 2024 Raditya. + +#include "carla_pointcloud_interface/carla_pointcloud_interface_node.hpp" #include From 0cb5ca47e1a4546cf3ea59b3aa747b2894e63872 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 15 Mar 2024 17:42:53 +0900 Subject: [PATCH 04/50] remove redundancy and added remap --- .../launch/carla_autoware.launch.xml | 7 +- .../launch/carla_ros.launch.xml | 2 +- .../launch/e2e_simulator.launch.xml | 84 ------------------- .../carla_autoware/resource/carla_autoware | 0 .../carla_gnss_interface_node.hpp | 14 +++- .../carla_gnss_interface_node.cpp | 14 +++- .../carla_pointcloud_interface_node.hpp | 18 +++- .../carla_pointcloud_interface_node.cpp | 23 ++--- 8 files changed, 59 insertions(+), 103 deletions(-) delete mode 100644 simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml delete mode 100644 simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware diff --git a/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml index 1e71edcd8eb39..54bf9db5019d3 100644 --- a/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml @@ -3,8 +3,11 @@ - + - + + + + diff --git a/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml index a3b1b892b68fb..1bed1146b4820 100644 --- a/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml +++ b/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml deleted file mode 100644 index 8226a45c29088..0000000000000 --- a/simulator/CARLA_Autoware/carla_autoware/launch/e2e_simulator.launch.xml +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware b/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware deleted file mode 100644 index e69de29bb2d1d..0000000000000 diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index fec3c7c909dd8..48b1aca5d0ec4 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -1,4 +1,16 @@ -// Copyright 2024 Raditya. +// Copyright 2024 Autoware Foundation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. #ifndef CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ #define CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 0496371a66be9..9b118e5762a9a 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -1,4 +1,16 @@ -// Copyright 2024 Raditya. +// Copyright 2024 Autoware Foundation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. #include "carla_gnss_interface/carla_gnss_interface_node.hpp" diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp index 75be0b56e9dbe..1498321c1fe7a 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp @@ -1,4 +1,16 @@ -// Copyright 2024 Raditya. +// Copyright 2024 Autoware Foundation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. #ifndef CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ #define CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ @@ -23,10 +35,8 @@ class PointCloudInterface : public rclcpp::Node private: std::shared_ptr tf_buffer_; - rclcpp::Publisher::SharedPtr velodyne_points_raw; - rclcpp::Publisher::SharedPtr velodyne_points_top; - rclcpp::Publisher::SharedPtr velodyne_points_con; std::shared_ptr tf_listener_; + rclcpp::Publisher::SharedPtr velodyne_points_raw; rclcpp::Subscription::SharedPtr carla_cloud_; std::string tf_output; void processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg); diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp index b3981d9bfc3f8..187553da913eb 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp @@ -1,12 +1,21 @@ -// Copyright 2024 Raditya. +// Copyright 2024 Autoware Foundation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. #include "carla_pointcloud_interface/carla_pointcloud_interface_node.hpp" #include -#include -#include - #include void PointCloudInterface::processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg) @@ -15,8 +24,6 @@ void PointCloudInterface::processScan(const sensor_msgs::msg::PointCloud2::Share sensor_msgs::msg::PointCloud2 transformed_cloud; if (pcl_ros::transformPointCloud(tf_output, *scanMsg, transformed_cloud, *tf_buffer_)) { transformed_cloud.header.stamp = scanMsg->header.stamp; - velodyne_points_top->publish(transformed_cloud); - velodyne_points_con->publish(transformed_cloud); velodyne_points_raw->publish(transformed_cloud); } } @@ -42,10 +49,6 @@ PointCloudInterface::PointCloudInterface(const rclcpp::NodeOptions & node_option setupTF(); velodyne_points_raw = this->create_publisher("/points_raw", rclcpp::SensorDataQoS()); - velodyne_points_top = this->create_publisher( - "/sensing/lidar/top/outlier_filtered/pointcloud", rclcpp::SensorDataQoS()); - velodyne_points_con = this->create_publisher( - "/sensing/lidar/concatenated/pointcloud", rclcpp::SensorDataQoS()); } } From dbe567bc9ca13d580c10e307141841856bd681ca Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 15 Mar 2024 17:54:22 +0900 Subject: [PATCH 05/50] fixed cmake by adding autoware_package --- simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt | 3 +++ simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt | 4 ++++ 2 files changed, 7 insertions(+) diff --git a/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt b/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt index deb641375684e..c51fe86d73706 100644 --- a/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 3.8) project(carla_autoware) +find_package(autoware_cmake REQUIRED) +autoware_package() + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt index 75d8490890e4c..9715894c554ce 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt @@ -1,5 +1,9 @@ cmake_minimum_required(VERSION 3.5) project(carla_gnss_interface) + +find_package(autoware_cmake REQUIRED) +autoware_package() + if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() From 791747d2f662ecdd6a13b6e84e1e93c289677d34 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Tue, 19 Mar 2024 12:39:48 +0900 Subject: [PATCH 06/50] encapsulate some function Signed-off-by: mraditya01 --- .../carla_gnss_interface_node.hpp | 35 +++++++----- .../carla_gnss_interface_node.cpp | 54 ++++++++++--------- .../carla_pointcloud_interface/CMakeLists.txt | 4 ++ 3 files changed, 55 insertions(+), 38 deletions(-) diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index 48b1aca5d0ec4..06823c2971fb3 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -88,30 +88,37 @@ class GPSPoint class WayPoint { public: - GPSPoint pos; - WayPoint() {} + GPSPoint pos; + WayPoint() {} + + WayPoint(const double & x, const double & y, const double & z, const double & a) + { + pos.x = x; + pos.y = y; + pos.z = z; + pos.a = a; + } +}; - WayPoint(const double & x, const double & y, const double & z, const double & a) - { - pos.x = x; - pos.y = y; - pos.z = z; - pos.a = a; - } +struct MappingParameters { + std::string proj_str; + WayPoint org; + double lat; + double lon; + double alt; }; class MappingUtils { public: - MappingUtils(); - virtual ~MappingUtils(); + MappingUtils(); + virtual ~MappingUtils(); - static void llaToxyz( - const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon, - const double & alt, double & x_out, double & y_out, double & z_out); + static void llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out); }; } // namespace gnss } // namespace interface + #endif // CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 9b118e5762a9a..0079f4883eb9e 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -21,33 +21,29 @@ namespace interface namespace gnss { -MappingUtils::MappingUtils() -{ -} +MappingUtils::MappingUtils() {} -MappingUtils::~MappingUtils() -{ -} +MappingUtils::~MappingUtils() {} -void MappingUtils::llaToxyz( - const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon, - const double & alt, double & x_out, double & y_out, double & z_out) -{ - if (proj_str.size() < 8) return; +void MappingUtils::llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out) { + if (params.proj_str.size() < 8) return; - PJ_CONTEXT * C = proj_context_create(); - PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", proj_str.c_str(), NULL); + PJ_CONTEXT *C = proj_context_create(); + PJ *P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); - if (P == 0) return; + if (P == nullptr) { + proj_context_destroy(C); + return; + } - PJ_COORD gps_degrees = proj_coord(lat, lon, alt, 0); - PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); - x_out = xyz_out.enu.e + origin.pos.x; - y_out = xyz_out.enu.n + origin.pos.y; - z_out = xyz_out.enu.u + origin.pos.z; + PJ_COORD gps_degrees = proj_coord(params.lat, params.lon, params.alt, 0); + PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); + x_out = xyz_out.enu.e + params.org.pos.x; + y_out = xyz_out.enu.n + params.org.pos.y; + z_out = xyz_out.enu.u + params.org.pos.z; - proj_destroy(P); - proj_context_destroy(C); + proj_destroy(P); + proj_context_destroy(C); } } // namespace gnss } // namespace interface @@ -57,9 +53,19 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms geometry_msgs::msg::PoseStamped pose_; geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; interface::gnss::WayPoint origin, p; - interface::gnss::MappingUtils::llaToxyz( - "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs", origin, - msg->latitude, msg->longitude, msg->altitude, p.pos.x, p.pos.y, p.pos.z); + // Create an instance of MappingUtils + interface::gnss::MappingUtils mappingUtils; + + // Create MappingParameters struct to hold the parameters + interface::gnss::MappingParameters params; + params.proj_str = "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs"; + params.lat = msg->latitude; + params.lon = msg->longitude; + params.alt = msg->altitude; + + // Call llaToxyz function + mappingUtils.llaToxyz(params, p.pos.x, p.pos.y, p.pos.z); + pose_.header = msg->header; pose_.header.frame_id = "map"; pose_.pose.position.x = p.pos.x; diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt index 43f49410ed151..692423f6d8aa0 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt @@ -1,4 +1,8 @@ cmake_minimum_required(VERSION 3.5) + +find_package(autoware_cmake REQUIRED) +autoware_package() + project(carla_pointcloud_interface) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) From ad6d4a27bfd463415d6b220c8167e78605472573 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 19 Mar 2024 03:41:59 +0000 Subject: [PATCH 07/50] style(pre-commit): autofix --- .../carla_gnss_interface_node.hpp | 41 +++++++++--------- .../carla_gnss_interface_node.cpp | 43 +++++++++++-------- 2 files changed, 46 insertions(+), 38 deletions(-) diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index 06823c2971fb3..47e6d3821e1cc 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -88,37 +88,38 @@ class GPSPoint class WayPoint { public: - GPSPoint pos; - WayPoint() {} - - WayPoint(const double & x, const double & y, const double & z, const double & a) - { - pos.x = x; - pos.y = y; - pos.z = z; - pos.a = a; - } + GPSPoint pos; + WayPoint() {} + + WayPoint(const double & x, const double & y, const double & z, const double & a) + { + pos.x = x; + pos.y = y; + pos.z = z; + pos.a = a; + } }; -struct MappingParameters { - std::string proj_str; - WayPoint org; - double lat; - double lon; - double alt; +struct MappingParameters +{ + std::string proj_str; + WayPoint org; + double lat; + double lon; + double alt; }; class MappingUtils { public: - MappingUtils(); - virtual ~MappingUtils(); + MappingUtils(); + virtual ~MappingUtils(); - static void llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out); + static void llaToxyz( + const MappingParameters & params, double & x_out, double & y_out, double & z_out); }; } // namespace gnss } // namespace interface - #endif // CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 0079f4883eb9e..468498b0d294a 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -21,29 +21,35 @@ namespace interface namespace gnss { -MappingUtils::MappingUtils() {} +MappingUtils::MappingUtils() +{ +} -MappingUtils::~MappingUtils() {} +MappingUtils::~MappingUtils() +{ +} -void MappingUtils::llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out) { - if (params.proj_str.size() < 8) return; +void MappingUtils::llaToxyz( + const MappingParameters & params, double & x_out, double & y_out, double & z_out) +{ + if (params.proj_str.size() < 8) return; - PJ_CONTEXT *C = proj_context_create(); - PJ *P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); + PJ_CONTEXT * C = proj_context_create(); + PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); - if (P == nullptr) { - proj_context_destroy(C); - return; - } + if (P == nullptr) { + proj_context_destroy(C); + return; + } - PJ_COORD gps_degrees = proj_coord(params.lat, params.lon, params.alt, 0); - PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); - x_out = xyz_out.enu.e + params.org.pos.x; - y_out = xyz_out.enu.n + params.org.pos.y; - z_out = xyz_out.enu.u + params.org.pos.z; + PJ_COORD gps_degrees = proj_coord(params.lat, params.lon, params.alt, 0); + PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); + x_out = xyz_out.enu.e + params.org.pos.x; + y_out = xyz_out.enu.n + params.org.pos.y; + z_out = xyz_out.enu.u + params.org.pos.z; - proj_destroy(P); - proj_context_destroy(C); + proj_destroy(P); + proj_context_destroy(C); } } // namespace gnss } // namespace interface @@ -58,7 +64,8 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms // Create MappingParameters struct to hold the parameters interface::gnss::MappingParameters params; - params.proj_str = "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs"; + params.proj_str = + "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs"; params.lat = msg->latitude; params.lon = msg->longitude; params.alt = msg->altitude; From ea9946e18e5812895c5228e831278bc6565122d2 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Tue, 19 Mar 2024 18:24:50 +0900 Subject: [PATCH 08/50] fix build issues Signed-off-by: Maxime CLEMENT --- .../carla_autoware/resource/carla_autoware | 0 .../carla_pointcloud_interface/CMakeLists.txt | 49 +------------------ .../carla_pointcloud_interface/package.xml | 14 +----- 3 files changed, 2 insertions(+), 61 deletions(-) create mode 100644 simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware diff --git a/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware b/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt index 692423f6d8aa0..832614f41a24f 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt @@ -1,50 +1,12 @@ cmake_minimum_required(VERSION 3.5) +project(carla_pointcloud_interface) find_package(autoware_cmake REQUIRED) autoware_package() -project(carla_pointcloud_interface) -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) -endif() - -if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) -endif() - - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - - -find_package(Boost COMPONENTS signals) find_package(PCL REQUIRED COMPONENTS common) - - -find_package(PkgConfig REQUIRED) -pkg_check_modules(YAML_CPP REQUIRED yaml-cpp) -find_path(YAML_CPP_INCLUDE_DIR - NAMES yaml_cpp.h - PATHS ${YAML_CPP_INCLUDE_DIRS}) -find_library(YAML_CPP_LIBRARY - NAMES YAML_CPP - PATHS ${YAML_CPP_LIBRARY_DIRS}) - -find_package(OpenCV REQUIRED) - -link_directories(${YAML_CPP_LIBRARY_DIRS}) - -if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") - add_definitions(-DHAVE_NEW_YAMLCPP) -endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") - include_directories( - ${OpenCV_INCLUDE_DIRS} ${PCL_COMMON_INCLUDE_DIRS} ) @@ -52,20 +14,11 @@ ament_auto_add_library(carla_pointcloud_interface SHARED src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp ) - -# workaround to allow deprecated header to build on both galactic and rolling -if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) - target_compile_definitions(carla_pointcloud_interface PRIVATE - USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER - ) -endif() - rclcpp_components_register_node(carla_pointcloud_interface PLUGIN "PointCloudInterface" EXECUTABLE carla_pointcloud_interface_node ) - ament_auto_package( INSTALL_TO_SHARE launch diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml b/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml index 5272a666d9ee0..efca9e80b54f6 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml @@ -7,27 +7,15 @@ Muhammad Raditya Giovanni Apache License 2.0 - ament_cmake_auto + autoware_cmake - angles - autoware_auto_control_msgs - autoware_auto_vehicle_msgs - cv_bridge - diagnostic_updater - geometry_msgs - image_transport libpcl-all-dev - message_filters - pcl_conversions pcl_ros rclcpp rclcpp_components sensor_msgs tf2 tf2_ros - velodyne_msgs - visualization_msgs - yaml-cpp ament_cmake From 91dc64f561cd99106e0ec54975616141009794c5 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 22 Mar 2024 12:03:19 +0900 Subject: [PATCH 09/50] cleaning some issues Signed-off-by: mraditya01 --- .../carla_autoware/config/objects.json | 10 ----- .../CARLA_Autoware/carla_autoware/package.xml | 7 ++-- .../CARLA_Autoware/carla_autoware/setup.py | 2 +- .../src/carla_autoware/carla_autoware.py | 13 ++----- .../carla_gnss_interface_node.hpp | 19 +-------- .../carla_gnss_interface_node.cpp | 13 +------ .../carla_pointcloud_interface/CMakeLists.txt | 39 ++++++++++++++++++- .../carla_pointcloud_interface_node.hpp | 1 - .../carla_pointcloud_interface_node.cpp | 4 -- 9 files changed, 50 insertions(+), 58 deletions(-) diff --git a/simulator/CARLA_Autoware/carla_autoware/config/objects.json b/simulator/CARLA_Autoware/carla_autoware/config/objects.json index ac6b39666ec5f..914a373af56d1 100644 --- a/simulator/CARLA_Autoware/carla_autoware/config/objects.json +++ b/simulator/CARLA_Autoware/carla_autoware/config/objects.json @@ -16,10 +16,6 @@ "type": "sensor.pseudo.markers", "id": "markers" }, - { - "type": "sensor.pseudo.opendrive_map", - "id": "map" - }, { "type": "vehicle.toyota.prius", "id": "ego_vehicle", @@ -58,12 +54,6 @@ "rotation_frequency": 20, "noise_stddev": 0.0 }, - { - "type": "sensor.opendrive_map", - "id": "OpenDRIVE", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0 } - }, - { "type": "sensor.other.gnss", "id": "gnss", diff --git a/simulator/CARLA_Autoware/carla_autoware/package.xml b/simulator/CARLA_Autoware/carla_autoware/package.xml index 4cad00c7420fa..0ffc706488dd5 100644 --- a/simulator/CARLA_Autoware/carla_autoware/package.xml +++ b/simulator/CARLA_Autoware/carla_autoware/package.xml @@ -2,9 +2,10 @@ carla_autoware 0.0.0 - The carla_manual_control package - CARLA Simulator Team - MIT + The carla autoware bridge package + Muhammad Raditya Giovanni + Maxime CLEMENT + Apache License 2.0 ros2launch ros_compatibility diff --git a/simulator/CARLA_Autoware/carla_autoware/setup.py b/simulator/CARLA_Autoware/carla_autoware/setup.py index 139f98586afc6..75676e9485abb 100644 --- a/simulator/CARLA_Autoware/carla_autoware/setup.py +++ b/simulator/CARLA_Autoware/carla_autoware/setup.py @@ -32,7 +32,7 @@ maintainer="mradityagio", maintainer_email="mradityagio@gmail.com", description="CARLA ROS2 bridge for AUTOWARE", - license="MIT", + license="Apache License 2.0", tests_require=["pytest"], entry_points={ "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], diff --git a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py index 6b00e37c67e86..848dc6b4aceda 100644 --- a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -17,8 +17,6 @@ class CarlaVehicleInterface(Node): def __init__(self): - rclpy.init(args=None) - super().__init__("carla_vehicle_interface_node") client = carla.Client("localhost", 2000) @@ -29,11 +27,7 @@ def __init__(self): self.target_vel = 0.0 self.vel_diff = 0.0 self.current_control = carla.VehicleControl() - self.ros2_node = rclpy.create_node("carla_autoware") - - self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) - self.spin_thread.start() - + # Publishes Topics used for AUTOWARE self.pub_vel_state = self.ros2_node.create_publisher( VelocityReport, "/vehicle/status/velocity_status", 1 @@ -142,8 +136,9 @@ def publish_gnss(self, msg): def main(args=None): - CarlaVehicleInterface() - + rclpy.init() + node = CarlaVehicleInterface() + rclpy.spin(node) if __name__ == "__main__": main() diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index 47e6d3821e1cc..2c6eaf56c6709 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -32,7 +32,6 @@ class GnssInterface : public rclcpp::Node { public: explicit GnssInterface(const rclcpp::NodeOptions & node_options); - virtual ~GnssInterface(); std::string tf_output_frame_; private: @@ -74,15 +73,6 @@ class GPSPoint alt = 0; dir = 0; } - - std::string ToString() - { - std::stringstream str; - str.precision(12); - str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; - str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; - return str.str(); - } }; class WayPoint @@ -109,15 +99,8 @@ struct MappingParameters double alt; }; -class MappingUtils -{ -public: - MappingUtils(); - virtual ~MappingUtils(); - static void llaToxyz( - const MappingParameters & params, double & x_out, double & y_out, double & z_out); -}; +void llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out); } // namespace gnss } // namespace interface diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 468498b0d294a..6ba444f47d751 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -25,14 +25,8 @@ MappingUtils::MappingUtils() { } -MappingUtils::~MappingUtils() -{ -} - -void MappingUtils::llaToxyz( - const MappingParameters & params, double & x_out, double & y_out, double & z_out) -{ - if (params.proj_str.size() < 8) return; +void MappingUtils::llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out) { + if (params.proj_str.size() < 8) return; PJ_CONTEXT * C = proj_context_create(); PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); @@ -86,9 +80,6 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms pup_pose_with_cov->publish(pose_cov_); } -GnssInterface::~GnssInterface() -{ -} GnssInterface::GnssInterface(const rclcpp::NodeOptions & node_options) : Node("gnss_interface_node", node_options), tf_output_frame_("base_link") diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt index 832614f41a24f..7a1d863761fb0 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt @@ -1,11 +1,39 @@ cmake_minimum_required(VERSION 3.5) -project(carla_pointcloud_interface) find_package(autoware_cmake REQUIRED) autoware_package() +project(carla_pointcloud_interface) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) +endif() + + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + + +find_package(Boost COMPONENTS signals) find_package(PCL REQUIRED COMPONENTS common) + + +find_package(PkgConfig REQUIRED) + +link_directories(${YAML_CPP_LIBRARY_DIRS}) + +if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") + add_definitions(-DHAVE_NEW_YAMLCPP) +endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") + include_directories( ${PCL_COMMON_INCLUDE_DIRS} ) @@ -14,11 +42,20 @@ ament_auto_add_library(carla_pointcloud_interface SHARED src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp ) + +# workaround to allow deprecated header to build on both galactic and rolling +if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) + target_compile_definitions(carla_pointcloud_interface PRIVATE + USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER + ) +endif() + rclcpp_components_register_node(carla_pointcloud_interface PLUGIN "PointCloudInterface" EXECUTABLE carla_pointcloud_interface_node ) + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp index 1498321c1fe7a..cc6bc5950cf81 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp @@ -31,7 +31,6 @@ class PointCloudInterface : public rclcpp::Node { public: explicit PointCloudInterface(const rclcpp::NodeOptions & node_options); - virtual ~PointCloudInterface(); private: std::shared_ptr tf_buffer_; diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp index 187553da913eb..27b89d7054408 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp @@ -35,10 +35,6 @@ void PointCloudInterface::setupTF() tf_listener_ = std::make_shared(*tf_buffer_); } -PointCloudInterface::~PointCloudInterface() -{ -} - PointCloudInterface::PointCloudInterface(const rclcpp::NodeOptions & node_options) : Node("carla_pointcloud_interface_node", node_options), tf_output("base_link") { From 3d203f324484ebfa40c5914afdcd3cc1394b91e6 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 22 Mar 2024 12:06:13 +0900 Subject: [PATCH 10/50] cleaning some issues Signed-off-by: mraditya01 --- .../carla_autoware/CMakeLists.txt | 33 --------------- .../CARLA_Autoware/carla_autoware/README.md | 16 ++++---- .../CARLA_Autoware/carla_autoware/package.xml | 2 - .../src/carla_autoware/carla_autoware.py | 41 +++++++------------ .../carla_gnss_interface_node.hpp | 3 +- .../carla_gnss_interface_node.cpp | 15 +++---- .../carla_pointcloud_interface/CMakeLists.txt | 8 +--- 7 files changed, 28 insertions(+), 90 deletions(-) diff --git a/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt b/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt index c51fe86d73706..f4471accbffd0 100644 --- a/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt @@ -8,39 +8,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() - - -# find dependencies -# uncomment the following section in order to fill in -# further dependencies manually. -# find_package( REQUIRED) -find_package(ament_cmake REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(sensor_msgs REQUIRED) -find_package(sensor_msgs_py REQUIRED) -find_package(datetime REQUIRED) - -find_package(rclpy REQUIRED) -find_package(tf2 REQUIRED) -find_package(tf2_ros REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(carla_msgs REQUIRED) -find_package(autoware_auto_vehicle_msgs REQUIRED) -find_package(autoware_auto_control_msgs REQUIRED) -find_package(tier4_debug_msgs REQUIRED) -find_package(tier4_system_msgs REQUIRED) -find_package(autoware_adapi_v1_msgs REQUIRED) -find_package(transform3d REQUIRED) -find_package(math REQUIRED) -find_package(numpy REQUIRED) -find_package(carla_data_provider REQUIRED) - - - - -find_package(ros_environment REQUIRED) -set(ROS_VERSION $ENV{ROS_VERSION}) - ament_export_dependencies(rclpy) # Install launch files. diff --git a/simulator/CARLA_Autoware/carla_autoware/README.md b/simulator/CARLA_Autoware/carla_autoware/README.md index cbf6f4e75f2b0..e77a9f920f6e2 100644 --- a/simulator/CARLA_Autoware/carla_autoware/README.md +++ b/simulator/CARLA_Autoware/carla_autoware/README.md @@ -6,15 +6,15 @@ This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). ( for ROS2 Humble) -- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.14-ubuntu-22.04). -- Add the egg file to the folder: ../CARLA_0.9.14/PythonAPI/carla/dist +- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04). +- Add the egg file to the folder: ../CARLA_0.9.15/PythonAPI/carla/dist - And install the wheel using pip. # Environment | ubuntu | ros | carla | autoware | | :----: | :----: | :----: | :-------------: | -| 22.04 | humble | 0.9.14 | universe/master | +| 22.04 | humble | 0.9.15 | universe/master | # Setup @@ -26,15 +26,13 @@ This ros package enables autonomous driving using Autoware in addition to the ba 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. -- Clone this repositories and ROSBridge +- Clone this repositories for ros-bridge on ROS2 Humble. ``` - git clone https://github.com/mraditya01/CARLA_Autoware.git git clone --recurse-submodules https://github.com/gezp/carla_ros.git -b humble-carla-0.9.14 + git clone https://github.com/astuff/astuff_sensor_msgs.git ``` -- Copy the files (sensor_kit_calibration.yaml, sensors.calibration.yaml) from folder "GNSS_interface/src/carla_sensor_kit_launch/carla_sensor_kit_description/config" to "src/param/autoware_individual_params/carla_sensor_kit". - ## build ```bash @@ -48,13 +46,13 @@ colcon build --symlink-install ```bash cd CARLA -./CarlaUE4.sh -prefernvidia -quality-level=Low +./CarlaUE4.sh -prefernvidia -quality-level=Low -RenderOffScreen ``` 2. Run ros nodes ```bash -ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit +ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit simulator_type:=carla ``` 3. Set initial pose (Init by GNSS) diff --git a/simulator/CARLA_Autoware/carla_autoware/package.xml b/simulator/CARLA_Autoware/carla_autoware/package.xml index 0ffc706488dd5..859139d93b1ce 100644 --- a/simulator/CARLA_Autoware/carla_autoware/package.xml +++ b/simulator/CARLA_Autoware/carla_autoware/package.xml @@ -13,7 +13,6 @@ astuff_sensor_msgs autoware_auto_control_msgs autoware_auto_vehicle_msgs - carla_data_provider carla_msgs datetime geometry_msgs @@ -25,7 +24,6 @@ sensor_msgs_py tf2 tf2_ros - transform3d ament_cmake diff --git a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py index 848dc6b4aceda..425dd4ea66221 100644 --- a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -1,5 +1,3 @@ -import threading - from autoware_auto_control_msgs.msg import AckermannControlCommand from autoware_auto_vehicle_msgs.msg import ControlModeReport from autoware_auto_vehicle_msgs.msg import GearReport @@ -20,51 +18,43 @@ def __init__(self): super().__init__("carla_vehicle_interface_node") client = carla.Client("localhost", 2000) - client.set_timeout(20) + client.set_timeout(30) self._world = client.get_world() self.current_vel = 0.0 self.target_vel = 0.0 self.vel_diff = 0.0 self.current_control = carla.VehicleControl() - + # Publishes Topics used for AUTOWARE - self.pub_vel_state = self.ros2_node.create_publisher( + self.pub_vel_state = self.create_publisher( VelocityReport, "/vehicle/status/velocity_status", 1 ) - self.pub_steering_state = self.ros2_node.create_publisher( + self.pub_steering_state = self.create_publisher( SteeringReport, "/vehicle/status/steering_status", 1 ) - self.pub_ctrl_mode = self.ros2_node.create_publisher( + self.pub_ctrl_mode = self.create_publisher( ControlModeReport, "/vehicle/status/control_mode", 1 ) - self.pub_gear_state = self.ros2_node.create_publisher( - GearReport, "/vehicle/status/gear_status", 1 - ) - self.pub_control = self.ros2_node.create_publisher( + self.pub_gear_state = self.create_publisher(GearReport, "/vehicle/status/gear_status", 1) + self.pub_control = self.create_publisher( CarlaEgoVehicleControl, "/carla/ego_vehicle/vehicle_control_cmd", 1 ) - self.vehicle_imu_publisher = self.ros2_node.create_publisher( - Imu, "/sensing/imu/tamagawa/imu_raw", 1 - ) - self.sensing_cloud_publisher = self.ros2_node.create_publisher( - PointCloud2, "/carla_pointcloud", 1 - ) + self.vehicle_imu_publisher = self.create_publisher(Imu, "/sensing/imu/tamagawa/imu_raw", 1) + self.sensing_cloud_publisher = self.create_publisher(PointCloud2, "/carla_pointcloud", 1) # Subscribe Topics used in Control - self.sub_status = self.ros2_node.create_subscription( + self.sub_status = self.create_subscription( CarlaEgoVehicleStatus, "/carla/ego_vehicle/vehicle_status", self.ego_status_callback, 1 ) - self.sub_control = self.ros2_node.create_subscription( + self.sub_control = self.create_subscription( AckermannControlCommand, "/control/command/control_cmd", self.control_callback, qos_profile=QoSProfile(depth=1), ) - self.sub_imu = self.ros2_node.create_subscription( - Imu, "/carla/ego_vehicle/imu", self.publish_imu, 1 - ) - self.sub_lidar = self.ros2_node.create_subscription( + self.sub_imu = self.create_subscription(Imu, "/carla/ego_vehicle/imu", self.publish_imu, 1) + self.sub_lidar = self.create_subscription( PointCloud2, "/carla/ego_vehicle/lidar", self.publish_lidar, @@ -130,15 +120,12 @@ def publish_imu(self, imu_msg): imu_msg.header.frame_id = "tamagawa/imu_link" self.vehicle_imu_publisher.publish(imu_msg) - def publish_gnss(self, msg): - """Publish GNSS to Autoware.""" - self.publisher_map.publish(msg) - def main(args=None): rclpy.init() node = CarlaVehicleInterface() rclpy.spin(node) + if __name__ == "__main__": main() diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp index 2c6eaf56c6709..a3a237fd5935c 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp @@ -99,8 +99,7 @@ struct MappingParameters double alt; }; - -void llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out); +void llaToxyz(const MappingParameters & params, double & x_out, double & y_out, double & z_out); } // namespace gnss } // namespace interface diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp index 6ba444f47d751..a12da2b13b014 100644 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp @@ -21,12 +21,9 @@ namespace interface namespace gnss { -MappingUtils::MappingUtils() +void llaToxyz(const MappingParameters & params, double & x_out, double & y_out, double & z_out) { -} - -void MappingUtils::llaToxyz(const MappingParameters ¶ms, double &x_out, double &y_out, double &z_out) { - if (params.proj_str.size() < 8) return; + if (params.proj_str.size() < 8) return; PJ_CONTEXT * C = proj_context_create(); PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); @@ -45,6 +42,7 @@ void MappingUtils::llaToxyz(const MappingParameters ¶ms, double &x_out, doub proj_destroy(P); proj_context_destroy(C); } + } // namespace gnss } // namespace interface @@ -53,11 +51,9 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms geometry_msgs::msg::PoseStamped pose_; geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; interface::gnss::WayPoint origin, p; - // Create an instance of MappingUtils - interface::gnss::MappingUtils mappingUtils; + interface::gnss::MappingParameters params; // Create MappingParameters struct to hold the parameters - interface::gnss::MappingParameters params; params.proj_str = "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs"; params.lat = msg->latitude; @@ -65,7 +61,7 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms params.alt = msg->altitude; // Call llaToxyz function - mappingUtils.llaToxyz(params, p.pos.x, p.pos.y, p.pos.z); + interface::gnss::llaToxyz(params, p.pos.x, p.pos.y, p.pos.z); pose_.header = msg->header; pose_.header.frame_id = "map"; @@ -80,7 +76,6 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms pup_pose_with_cov->publish(pose_cov_); } - GnssInterface::GnssInterface(const rclcpp::NodeOptions & node_options) : Node("gnss_interface_node", node_options), tf_output_frame_("base_link") { diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt index 7a1d863761fb0..66f98f9efabd5 100644 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt +++ b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt @@ -1,9 +1,9 @@ cmake_minimum_required(VERSION 3.5) +project(carla_pointcloud_interface) find_package(autoware_cmake REQUIRED) autoware_package() -project(carla_pointcloud_interface) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() @@ -28,12 +28,6 @@ find_package(PCL REQUIRED COMPONENTS common) find_package(PkgConfig REQUIRED) -link_directories(${YAML_CPP_LIBRARY_DIRS}) - -if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") - add_definitions(-DHAVE_NEW_YAMLCPP) -endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5") - include_directories( ${PCL_COMMON_INCLUDE_DIRS} ) From f599ceb14a7dd4eb03d62aa4eb5627f3f5dc2501 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 12 Apr 2024 18:20:21 +0900 Subject: [PATCH 11/50] fixed performance and rearrange some packages --- .pre-commit-config.yaml | 6 - .../carla_autoware/CMakeLists.txt | 0 .../carla_autoware/README.md | 15 +-- .../carla_autoware/config/objects.json | 37 ++---- .../launch/carla_autoware.launch.xml | 6 + .../launch/carla_ros.launch.xml | 16 +-- .../carla_autoware/package.xml | 1 + .../carla_autoware/resource/carla_autoware | 0 .../carla_autoware/setup.cfg | 0 .../carla_autoware/setup.py | 0 .../src/carla_autoware/carla_autoware.py | 91 +++++++++------ .../launch/carla_autoware.launch.xml | 13 --- .../carla_gnss_interface/CMakeLists.txt | 41 ------- .../carla_gnss_interface/README.md | 7 -- .../carla_gnss_interface_node.hpp | 107 ------------------ .../launch/gnss_interface.launch.xml | 5 - .../carla_gnss_interface/package.xml | 29 ----- .../carla_gnss_interface_node.cpp | 92 --------------- .../carla_pointcloud_interface/CMakeLists.txt | 56 --------- .../carla_pointcloud_interface/README.md | 11 -- .../carla_pointcloud_interface_node.hpp | 45 -------- .../launch/carla_pointcloud_interface.xml | 3 - .../carla_pointcloud_interface/package.xml | 23 ---- .../carla_pointcloud_interface_node.cpp | 52 --------- 24 files changed, 89 insertions(+), 567 deletions(-) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/CMakeLists.txt (100%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/README.md (73%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/config/objects.json (71%) create mode 100644 simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/launch/carla_ros.launch.xml (79%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/package.xml (96%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/resource/carla_autoware (100%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/setup.cfg (100%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/setup.py (100%) rename simulator/CARLA_Autoware/{ => CARLA_Autoware}/carla_autoware/src/carla_autoware/carla_autoware.py (67%) delete mode 100644 simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/README.md delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/package.xml delete mode 100644 simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/README.md delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml delete mode 100644 simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a5ca7b6cf37fa..7223a734c02d9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,12 +17,6 @@ repos: - id: trailing-whitespace args: [--markdown-linebreak-ext=md] - - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.33.0 - hooks: - - id: markdownlint - args: [-c, .markdownlint.yaml, --fix] - - repo: https://github.com/pre-commit/mirrors-prettier rev: v3.0.0-alpha.6 hooks: diff --git a/simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/CMakeLists.txt similarity index 100% rename from simulator/CARLA_Autoware/carla_autoware/CMakeLists.txt rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/CMakeLists.txt diff --git a/simulator/CARLA_Autoware/carla_autoware/README.md b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md similarity index 73% rename from simulator/CARLA_Autoware/carla_autoware/README.md rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md index e77a9f920f6e2..8e5abd137c67c 100644 --- a/simulator/CARLA_Autoware/carla_autoware/README.md +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md @@ -7,8 +7,7 @@ This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). ( for ROS2 Humble) - Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04). -- Add the egg file to the folder: ../CARLA_0.9.15/PythonAPI/carla/dist -- And install the wheel using pip. +- Install .whl using pip. # Environment @@ -22,15 +21,16 @@ This ros package enables autonomous driving using Autoware in addition to the ba - [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) -- [autoware containts](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) +- [Carla Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) +- [Carla Sensor Kit](https://github.com/mraditya01/carla_sensor_kit_launch) +- [Autoware Individual params (forked with CARLA Sensor Kit params)](https://github.com/mraditya01/autoware_individual_params) 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. -- Clone this repositories for ros-bridge on ROS2 Humble. +- Clone this repositories for CARLA ros-bridge on ROS2 Humble. ``` - git clone --recurse-submodules https://github.com/gezp/carla_ros.git -b humble-carla-0.9.14 - git clone https://github.com/astuff/astuff_sensor_msgs.git + git clone --recurse-submodules https://github.com/mraditya01/carla_ros_bridge.git ``` ## build @@ -52,7 +52,7 @@ cd CARLA 2. Run ros nodes ```bash -ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit simulator_type:=carla +ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit simulator_type:=carla ``` 3. Set initial pose (Init by GNSS) @@ -65,3 +65,4 @@ ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_ma - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. - You will also need to edit the `carla_sensor_kit_description` if you change the sensor configuration. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. +- Simulation time somtimes slowed down to 0.9x realtime. diff --git a/simulator/CARLA_Autoware/carla_autoware/config/objects.json b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/config/objects.json similarity index 71% rename from simulator/CARLA_Autoware/carla_autoware/config/objects.json rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/config/objects.json index 914a373af56d1..9e5d19731be03 100644 --- a/simulator/CARLA_Autoware/carla_autoware/config/objects.json +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/config/objects.json @@ -24,33 +24,19 @@ "type": "sensor.camera.rgb", "id": "rgb_front", "spawn_point": { "x": 0.7, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, - "image_size_x": 1280, - "image_size_y": 720, - "fov": 100.0 - }, - { - "type": "sensor.camera.rgb", - "id": "rgb_view", - "spawn_point": { "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0 }, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "attached_objects": [ - { - "type": "actor.pseudo.control", - "id": "control" - } - ] + "image_size_x": 480, + "image_size_y": 360, + "fov": 90.0 }, { "type": "sensor.lidar.ray_cast", "id": "lidar", "spawn_point": { "x": 0.0, "y": 0.0, "z": 2.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, + "channels": 64, + "points_per_second": 480000, + "upper_fov": 3.0, + "lower_fov": -27.0, "rotation_frequency": 20, "noise_stddev": 0.0 }, @@ -84,11 +70,6 @@ "id": "collision", "spawn_point": { "x": 0.0, "y": 0.0, "z": 0.0 } }, - { - "type": "sensor.other.lane_invasion", - "id": "lane_invasion", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 0.0 } - }, { "type": "sensor.pseudo.tf", "id": "tf" @@ -101,10 +82,6 @@ "type": "sensor.pseudo.odom", "id": "odometry" }, - { - "type": "sensor.pseudo.speedometer", - "id": "speedometer" - }, { "type": "actor.pseudo.control", "id": "control" diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml new file mode 100644 index 0000000000000..fc115f9ceaa53 --- /dev/null +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml similarity index 79% rename from simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml index 1bed1146b4820..1b8b9870f1ddf 100644 --- a/simulator/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml @@ -9,7 +9,7 @@ - + @@ -17,11 +17,12 @@ + - + @@ -32,6 +33,11 @@ + + + + + @@ -40,10 +46,4 @@ - - - - - - diff --git a/simulator/CARLA_Autoware/carla_autoware/package.xml b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/package.xml similarity index 96% rename from simulator/CARLA_Autoware/carla_autoware/package.xml rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/package.xml index 859139d93b1ce..de94dd7499ea2 100644 --- a/simulator/CARLA_Autoware/carla_autoware/package.xml +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/package.xml @@ -13,6 +13,7 @@ astuff_sensor_msgs autoware_auto_control_msgs autoware_auto_vehicle_msgs + carla_data_provider carla_msgs datetime geometry_msgs diff --git a/simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/resource/carla_autoware similarity index 100% rename from simulator/CARLA_Autoware/carla_autoware/resource/carla_autoware rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/resource/carla_autoware diff --git a/simulator/CARLA_Autoware/carla_autoware/setup.cfg b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.cfg similarity index 100% rename from simulator/CARLA_Autoware/carla_autoware/setup.cfg rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.cfg diff --git a/simulator/CARLA_Autoware/carla_autoware/setup.py b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.py similarity index 100% rename from simulator/CARLA_Autoware/carla_autoware/setup.py rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.py diff --git a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py similarity index 67% rename from simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py rename to simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py index 425dd4ea66221..92fef61976efc 100644 --- a/simulator/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py @@ -3,28 +3,21 @@ from autoware_auto_vehicle_msgs.msg import GearReport from autoware_auto_vehicle_msgs.msg import SteeringReport from autoware_auto_vehicle_msgs.msg import VelocityReport -import carla +from autoware_perception_msgs.msg import TrafficSignalArray from carla_msgs.msg import CarlaEgoVehicleControl from carla_msgs.msg import CarlaEgoVehicleStatus +from geometry_msgs.msg import PoseWithCovarianceStamped +from nav_msgs.msg import Odometry import rclpy from rclpy.node import Node -from rclpy.qos import QoSProfile -from sensor_msgs.msg import Imu -from sensor_msgs.msg import PointCloud2 class CarlaVehicleInterface(Node): def __init__(self): super().__init__("carla_vehicle_interface_node") - - client = carla.Client("localhost", 2000) - client.set_timeout(30) - - self._world = client.get_world() self.current_vel = 0.0 self.target_vel = 0.0 self.vel_diff = 0.0 - self.current_control = carla.VehicleControl() # Publishes Topics used for AUTOWARE self.pub_vel_state = self.create_publisher( @@ -40,33 +33,76 @@ def __init__(self): self.pub_control = self.create_publisher( CarlaEgoVehicleControl, "/carla/ego_vehicle/vehicle_control_cmd", 1 ) - self.vehicle_imu_publisher = self.create_publisher(Imu, "/sensing/imu/tamagawa/imu_raw", 1) - self.sensing_cloud_publisher = self.create_publisher(PointCloud2, "/carla_pointcloud", 1) + self.pub_traffic_signal_info = self.create_publisher( + TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 + ) + self.pub_pose_with_cov = self.create_publisher( + PoseWithCovarianceStamped, "/sensing/gnss/pose_with_covariance", 1 + ) # Subscribe Topics used in Control self.sub_status = self.create_subscription( CarlaEgoVehicleStatus, "/carla/ego_vehicle/vehicle_status", self.ego_status_callback, 1 ) self.sub_control = self.create_subscription( - AckermannControlCommand, - "/control/command/control_cmd", - self.control_callback, - qos_profile=QoSProfile(depth=1), + AckermannControlCommand, "/control/command/control_cmd", self.control_callback, 1 ) - self.sub_imu = self.create_subscription(Imu, "/carla/ego_vehicle/imu", self.publish_imu, 1) - self.sub_lidar = self.create_subscription( - PointCloud2, - "/carla/ego_vehicle/lidar", - self.publish_lidar, - qos_profile=QoSProfile(depth=1), + self.sub_odom = self.create_subscription( + Odometry, "/carla/ego_vehicle/odometry", self.pose_callback, 1 ) + def pose_callback(self, pose_msg): + out_pose_with_cov = PoseWithCovarianceStamped() + out_pose_with_cov.header.frame_id = "map" + out_pose_with_cov.header.stamp = pose_msg.header.stamp + out_pose_with_cov.pose.pose = pose_msg.pose.pose + out_pose_with_cov.pose.covariance = [ + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + ] + self.pub_pose_with_cov.publish(out_pose_with_cov) + def ego_status_callback(self, in_status): """Convert and publish CARLA Ego Vehicle Status to AUTOWARE.""" out_vel_state = VelocityReport() out_steering_state = SteeringReport() out_ctrl_mode = ControlModeReport() out_gear_state = GearReport() + out_traffic = TrafficSignalArray() out_vel_state.header = in_status.header out_vel_state.header.frame_id = "base_link" @@ -88,6 +124,7 @@ def ego_status_callback(self, in_status): self.pub_steering_state.publish(out_steering_state) self.pub_ctrl_mode.publish(out_ctrl_mode) self.pub_gear_state.publish(out_gear_state) + self.pub_traffic_signal_info.publish(out_traffic) def control_callback(self, in_cmd): """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" @@ -110,16 +147,6 @@ def control_callback(self, in_cmd): out_cmd.steer = -in_cmd.lateral.steering_tire_angle self.pub_control.publish(out_cmd) - def publish_lidar(self, lidar_msg): - """Publish LIDAR to Interface.""" - lidar_msg.header.frame_id = "velodyne_top" - self.sensing_cloud_publisher.publish(lidar_msg) - - def publish_imu(self, imu_msg): - """Publish IMU to Autoware.""" - imu_msg.header.frame_id = "tamagawa/imu_link" - self.vehicle_imu_publisher.publish(imu_msg) - def main(args=None): rclpy.init() diff --git a/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml deleted file mode 100644 index 54bf9db5019d3..0000000000000 --- a/simulator/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt deleted file mode 100644 index 9715894c554ce..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/CMakeLists.txt +++ /dev/null @@ -1,41 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(carla_gnss_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) -endif() - - -if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) -endif() - - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -find_package(PkgConfig REQUIRED) -pkg_check_modules(PROJ REQUIRED proj) - -ament_auto_add_library(carla_gnss_interface SHARED - src/carla_gnss_interface/carla_gnss_interface_node.cpp -) - -target_link_libraries(carla_gnss_interface ${PROJ_LIBRARIES}) - -rclcpp_components_register_node(carla_gnss_interface - PLUGIN "GnssInterface" - EXECUTABLE carla_gnss_interface_node -) - -ament_auto_package( - INSTALL_TO_SHARE - launch -) diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/README.md b/simulator/CARLA_Autoware/carla_gnss_interface/README.md deleted file mode 100644 index 8e3ec20befe68..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/README.md +++ /dev/null @@ -1,7 +0,0 @@ -# gnss Interface Node - -Convert GNSS CARLA messages to pose and pose with covariance - -1. Receive GNSS Messages: Subscribe to the GNSS messages published by CARLA `carla/ego_vehicle/gnss`. These messages typically include latitude, longitude, and altitude. - -2. Convert to ROS Pose and Pose with Covariance: Extract the position components (latitude, longitude, altitude) from the GNSS messages and create a ROS geometry_msgs/Pose and geometry_msgs/PoseWithCovariance message. Set the position fields (x, y, z) of the ROS Pose message by converting the corresponding latitude, longitude, and altitude values using proj. diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp b/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp deleted file mode 100644 index a3a237fd5935c..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// Copyright 2024 Autoware Foundation. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ -#define CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ - -#include "rclcpp/rclcpp.hpp" - -#include -#include -#include - -#include -#include - -#include -#include -#include - -class GnssInterface : public rclcpp::Node -{ -public: - explicit GnssInterface(const rclcpp::NodeOptions & node_options); - std::string tf_output_frame_; - -private: - rclcpp::Subscription::SharedPtr sub_gnss_fix; - rclcpp::Publisher::SharedPtr pup_pose; - rclcpp::Publisher::SharedPtr pup_pose_with_cov; - - void GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg); -}; - -namespace interface -{ -namespace gnss -{ - -class GPSPoint -{ -public: - double x, y, z; - double lat, lon, alt; - double dir, a; - - GPSPoint() - { - x = y = z = 0; - lat = lon = alt = 0; - dir = a = 0; - } - - GPSPoint(const double & x, const double & y, const double & z, const double & a) - { - this->x = x; - this->y = y; - this->z = z; - this->a = a; - - lat = 0; - lon = 0; - alt = 0; - dir = 0; - } -}; - -class WayPoint -{ -public: - GPSPoint pos; - WayPoint() {} - - WayPoint(const double & x, const double & y, const double & z, const double & a) - { - pos.x = x; - pos.y = y; - pos.z = z; - pos.a = a; - } -}; - -struct MappingParameters -{ - std::string proj_str; - WayPoint org; - double lat; - double lon; - double alt; -}; - -void llaToxyz(const MappingParameters & params, double & x_out, double & y_out, double & z_out); - -} // namespace gnss -} // namespace interface - -#endif // CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml b/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml deleted file mode 100644 index 6faf90f770022..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/launch/gnss_interface.launch.xml +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/package.xml b/simulator/CARLA_Autoware/carla_gnss_interface/package.xml deleted file mode 100644 index 74aeac6e9c643..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - carla_gnss_interface - 1.0.0 - Convert GNSS CARLA messages to pose and pose with covariance - Muhammad Raditya Giovanni - Apache License 2.0 - - ament_cmake_auto - - autoware_cmake - - angles - diagnostic_updater - geometry_msgs - message_filters - proj - rclcpp - rclcpp_components - sensor_msgs - tf2 - tf2_ros - tinyxml - - - ament_cmake - - diff --git a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp b/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp deleted file mode 100644 index a12da2b13b014..0000000000000 --- a/simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// Copyright 2024 Autoware Foundation. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "carla_gnss_interface/carla_gnss_interface_node.hpp" - -#include - -namespace interface -{ -namespace gnss -{ - -void llaToxyz(const MappingParameters & params, double & x_out, double & y_out, double & z_out) -{ - if (params.proj_str.size() < 8) return; - - PJ_CONTEXT * C = proj_context_create(); - PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL); - - if (P == nullptr) { - proj_context_destroy(C); - return; - } - - PJ_COORD gps_degrees = proj_coord(params.lat, params.lon, params.alt, 0); - PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees); - x_out = xyz_out.enu.e + params.org.pos.x; - y_out = xyz_out.enu.n + params.org.pos.y; - z_out = xyz_out.enu.u + params.org.pos.z; - - proj_destroy(P); - proj_context_destroy(C); -} - -} // namespace gnss -} // namespace interface - -void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr msg) -{ - geometry_msgs::msg::PoseStamped pose_; - geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_; - interface::gnss::WayPoint origin, p; - interface::gnss::MappingParameters params; - - // Create MappingParameters struct to hold the parameters - params.proj_str = - "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs"; - params.lat = msg->latitude; - params.lon = msg->longitude; - params.alt = msg->altitude; - - // Call llaToxyz function - interface::gnss::llaToxyz(params, p.pos.x, p.pos.y, p.pos.z); - - pose_.header = msg->header; - pose_.header.frame_id = "map"; - pose_.pose.position.x = p.pos.x; - pose_.pose.position.y = p.pos.y; - pose_.pose.position.z = p.pos.z; - - pose_cov_.header = pose_.header; - pose_cov_.pose.pose = pose_.pose; - - pup_pose->publish(pose_); - pup_pose_with_cov->publish(pose_cov_); -} - -GnssInterface::GnssInterface(const rclcpp::NodeOptions & node_options) -: Node("gnss_interface_node", node_options), tf_output_frame_("base_link") -{ - sub_gnss_fix = this->create_subscription( - "carla/ego_vehicle/gnss", 1, - std::bind(&GnssInterface::GnssCallBack, this, std::placeholders::_1)); - - pup_pose = this->create_publisher("/sensing/gnss/pose", 1); - pup_pose_with_cov = this->create_publisher( - "/sensing/gnss/pose_with_covariance", 1); -} - -#include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(GnssInterface) diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt b/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt deleted file mode 100644 index 66f98f9efabd5..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt +++ /dev/null @@ -1,56 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(carla_pointcloud_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) -endif() - -if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wno-gnu-anonymous-struct -Wno-nested-anon-types ) -endif() - - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - - -find_package(Boost COMPONENTS signals) -find_package(PCL REQUIRED COMPONENTS common) - - - -find_package(PkgConfig REQUIRED) - -include_directories( - ${PCL_COMMON_INCLUDE_DIRS} -) - -ament_auto_add_library(carla_pointcloud_interface SHARED - src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp -) - - -# workaround to allow deprecated header to build on both galactic and rolling -if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0) - target_compile_definitions(carla_pointcloud_interface PRIVATE - USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER - ) -endif() - -rclcpp_components_register_node(carla_pointcloud_interface - PLUGIN "PointCloudInterface" - EXECUTABLE carla_pointcloud_interface_node -) - - -ament_auto_package( - INSTALL_TO_SHARE - launch -) diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md b/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md deleted file mode 100644 index c47a171bfc415..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/README.md +++ /dev/null @@ -1,11 +0,0 @@ -# carla_pointcloud_interface - -Relaying subscribed message from CARLA to Autoware related LIDAR topic message. - -Message Subscribed: -`carla_pointcloud` - -Message Published: -`/points_raw` -`/sensing/lidar/top/outlier_filtered/pointcloud` -`/sensing/lidar/concatenated/pointcloud` diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp deleted file mode 100644 index cc6bc5950cf81..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/include/carla_pointcloud_interface/carla_pointcloud_interface_node.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// Copyright 2024 Autoware Foundation. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ -#define CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ - -#include "rclcpp/rclcpp.hpp" - -#include - -#include -#include -#include - -#include -#include -#include - -class PointCloudInterface : public rclcpp::Node -{ -public: - explicit PointCloudInterface(const rclcpp::NodeOptions & node_options); - -private: - std::shared_ptr tf_buffer_; - std::shared_ptr tf_listener_; - rclcpp::Publisher::SharedPtr velodyne_points_raw; - rclcpp::Subscription::SharedPtr carla_cloud_; - std::string tf_output; - void processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg); - void setupTF(); -}; - -#endif // CARLA_POINTCLOUD_INTERFACE__CARLA_POINTCLOUD_INTERFACE_NODE_HPP_ diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml b/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml deleted file mode 100644 index 2b53ad1b2a50b..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/launch/carla_pointcloud_interface.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml b/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml deleted file mode 100644 index efca9e80b54f6..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - carla_pointcloud_interface - 1.0.0 - Convert CARLA 4D point cloud message to Autoware XYZIRADT cloud message - Muhammad Raditya Giovanni - Apache License 2.0 - - autoware_cmake - - libpcl-all-dev - pcl_ros - rclcpp - rclcpp_components - sensor_msgs - tf2 - tf2_ros - - - ament_cmake - - diff --git a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp b/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp deleted file mode 100644 index 27b89d7054408..0000000000000 --- a/simulator/CARLA_Autoware/carla_pointcloud_interface/src/carla_pointcloud_interface/carla_pointcloud_interface_node.cpp +++ /dev/null @@ -1,52 +0,0 @@ -// Copyright 2024 Autoware Foundation. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "carla_pointcloud_interface/carla_pointcloud_interface_node.hpp" - -#include - -#include - -void PointCloudInterface::processScan(const sensor_msgs::msg::PointCloud2::SharedPtr scanMsg) -{ - { - sensor_msgs::msg::PointCloud2 transformed_cloud; - if (pcl_ros::transformPointCloud(tf_output, *scanMsg, transformed_cloud, *tf_buffer_)) { - transformed_cloud.header.stamp = scanMsg->header.stamp; - velodyne_points_raw->publish(transformed_cloud); - } - } -} - -void PointCloudInterface::setupTF() -{ - tf_buffer_ = std::make_shared(this->get_clock()); - tf_listener_ = std::make_shared(*tf_buffer_); -} - -PointCloudInterface::PointCloudInterface(const rclcpp::NodeOptions & node_options) -: Node("carla_pointcloud_interface_node", node_options), tf_output("base_link") -{ - carla_cloud_ = this->create_subscription( - "carla_pointcloud", rclcpp::SensorDataQoS(), - std::bind(&PointCloudInterface::processScan, this, std::placeholders::_1)); - { - setupTF(); - velodyne_points_raw = - this->create_publisher("/points_raw", rclcpp::SensorDataQoS()); - } -} - -#include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(PointCloudInterface) From adf1cb6c51b11298c98c19cd8533c8d9f6f3ce87 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 15 Apr 2024 15:03:04 +0900 Subject: [PATCH 12/50] fixed package names --- .../CARLA_Autoware => }/carla_autoware/CMakeLists.txt | 0 .../CARLA_Autoware => }/carla_autoware/README.md | 2 +- .../CARLA_Autoware => }/carla_autoware/config/objects.json | 0 .../carla_autoware/launch/carla_autoware.launch.xml | 0 .../carla_autoware/launch/carla_ros.launch.xml | 0 .../CARLA_Autoware => }/carla_autoware/package.xml | 0 .../carla_autoware/resource/carla_autoware | 0 .../CARLA_Autoware => }/carla_autoware/setup.cfg | 0 .../CARLA_Autoware => }/carla_autoware/setup.py | 5 +++-- .../carla_autoware/src/carla_autoware/carla_autoware.py | 0 10 files changed, 4 insertions(+), 3 deletions(-) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/CMakeLists.txt (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/README.md (96%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/config/objects.json (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/launch/carla_autoware.launch.xml (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/launch/carla_ros.launch.xml (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/package.xml (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/resource/carla_autoware (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/setup.cfg (100%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/setup.py (81%) rename simulator/{CARLA_Autoware/CARLA_Autoware => }/carla_autoware/src/carla_autoware/carla_autoware.py (100%) diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/CMakeLists.txt b/simulator/carla_autoware/CMakeLists.txt similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/CMakeLists.txt rename to simulator/carla_autoware/CMakeLists.txt diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md b/simulator/carla_autoware/README.md similarity index 96% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md rename to simulator/carla_autoware/README.md index 8e5abd137c67c..6691bc6517410 100644 --- a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -21,7 +21,7 @@ This ros package enables autonomous driving using Autoware in addition to the ba - [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) -- [Carla Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) +- [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) - [Carla Sensor Kit](https://github.com/mraditya01/carla_sensor_kit_launch) - [Autoware Individual params (forked with CARLA Sensor Kit params)](https://github.com/mraditya01/autoware_individual_params) 1. Download maps (y-axis inverted version) to arbitaly location diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/config/objects.json rename to simulator/carla_autoware/config/objects.json diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_autoware.launch.xml rename to simulator/carla_autoware/launch/carla_autoware.launch.xml diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml b/simulator/carla_autoware/launch/carla_ros.launch.xml similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/launch/carla_ros.launch.xml rename to simulator/carla_autoware/launch/carla_ros.launch.xml diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/package.xml b/simulator/carla_autoware/package.xml similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/package.xml rename to simulator/carla_autoware/package.xml diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/resource/carla_autoware b/simulator/carla_autoware/resource/carla_autoware similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/resource/carla_autoware rename to simulator/carla_autoware/resource/carla_autoware diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.cfg b/simulator/carla_autoware/setup.cfg similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.cfg rename to simulator/carla_autoware/setup.cfg diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.py b/simulator/carla_autoware/setup.py similarity index 81% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.py rename to simulator/carla_autoware/setup.py index 75676e9485abb..82dfb6581d776 100644 --- a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -23,9 +23,10 @@ packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), - ("share/" + package_name, glob("config/*.json")), + ("share/" + package_name, glob("config/objects.json")), ("share/" + package_name, ["package.xml"]), - (os.path.join("share", package_name), glob("launch/*.launch.xml")), + (os.path.join("share", package_name), glob("launch/carla_autoware.launch.xml")), + (os.path.join("share", package_name), glob("launch/carla_ros.launch.xml")), ], install_requires=["setuptools"], zip_safe=True, diff --git a/simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py similarity index 100% rename from simulator/CARLA_Autoware/CARLA_Autoware/carla_autoware/src/carla_autoware/carla_autoware.py rename to simulator/carla_autoware/src/carla_autoware/carla_autoware.py From 318aaed429496065c4b7f8e7701296cdf0e5b493 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 22 Apr 2024 16:02:36 +0900 Subject: [PATCH 13/50] updated without carlarosbridge dependencies --- simulator/carla_autoware/CMakeLists.txt | 12 +- simulator/carla_autoware/LICENSE | 201 +++++ simulator/carla_autoware/README.md | 13 +- simulator/carla_autoware/config/objects.json | 125 +-- .../launch/carla_autoware.launch.xml | 34 +- .../launch/carla_ros.launch.xml | 49 - simulator/carla_autoware/package.xml | 5 - simulator/carla_autoware/setup.py | 63 +- .../src/carla_autoware/carla_autoware.py | 298 +++--- .../src/carla_autoware/carla_ros.py | 420 +++++++++ .../modules/carla_data_provider.py | 853 ++++++++++++++++++ .../src/carla_autoware/modules/carla_utils.py | 99 ++ .../carla_autoware/modules/carla_wrapper.py | 227 +++++ 13 files changed, 2061 insertions(+), 338 deletions(-) create mode 100644 simulator/carla_autoware/LICENSE delete mode 100644 simulator/carla_autoware/launch/carla_ros.launch.xml create mode 100644 simulator/carla_autoware/src/carla_autoware/carla_ros.py create mode 100644 simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py create mode 100644 simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py create mode 100644 simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py diff --git a/simulator/carla_autoware/CMakeLists.txt b/simulator/carla_autoware/CMakeLists.txt index f4471accbffd0..1062fd0247b07 100644 --- a/simulator/carla_autoware/CMakeLists.txt +++ b/simulator/carla_autoware/CMakeLists.txt @@ -4,11 +4,20 @@ project(carla_autoware) find_package(autoware_cmake REQUIRED) autoware_package() +find_package( + catkin REQUIRED COMPONENTS rospy std_msgs + carla_msgs) + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -ament_export_dependencies(rclpy) +ament_export_dependencies(rclpy rospy) + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + # Install launch files. install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) @@ -17,6 +26,7 @@ install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) ament_auto_package( launch resource + config src ) ament_package() diff --git a/simulator/carla_autoware/LICENSE b/simulator/carla_autoware/LICENSE new file mode 100644 index 0000000000000..261eeb9e9f8b2 --- /dev/null +++ b/simulator/carla_autoware/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 6691bc6517410..4e1300e274e77 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -4,10 +4,9 @@ ### Thanks to for ROS2 Humble support for CARLA ROS bridge -This ros package enables autonomous driving using Autoware in addition to the basic function of the official [ros-bridge](https://github.com/carla-simulator/ros-bridge) package (communication between ros and carla). ( for ROS2 Humble) +This ros package enables communication between Autoware and CARLA for autonomous driving simulation. -- Make sure to Download the Python egg for 3.10 from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04). -- Install .whl using pip. +- Make sure to Install the python .whl using pip to use CARLA with ROS2 Humble from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04). # Environment @@ -24,14 +23,11 @@ This ros package enables autonomous driving using Autoware in addition to the ba - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) - [Carla Sensor Kit](https://github.com/mraditya01/carla_sensor_kit_launch) - [Autoware Individual params (forked with CARLA Sensor Kit params)](https://github.com/mraditya01/autoware_individual_params) +- [Autoware launch with CARLA option](https://github.com/mraditya01/autoware_launch) + 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. -- Clone this repositories for CARLA ros-bridge on ROS2 Humble. - - ``` - git clone --recurse-submodules https://github.com/mraditya01/carla_ros_bridge.git - ``` ## build @@ -65,4 +61,3 @@ ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. - You will also need to edit the `carla_sensor_kit_description` if you change the sensor configuration. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. -- Simulation time somtimes slowed down to 0.9x realtime. diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index 9e5d19731be03..4cc82a2743cf0 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -1,92 +1,55 @@ { - "objects": [ + "sensors": [ { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" + "type": "sensor.camera.rgb", + "id": "rgb_front", + "spawn_point": { + "x": 0.7, + "y": 0.0, + "z": 1.6, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "image_size_x": 480, + "image_size_y": 360, + "fov": 90.0 }, { - "type": "sensor.pseudo.objects", - "id": "objects" + "type": "sensor.lidar.ray_cast", + "id": "lidar", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 2.6, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "range": 50, + "channels": 64, + "points_per_second": 480000, + "upper_fov": 3.0, + "lower_fov": -27.0, + "rotation_frequency": 20, + "noise_stddev": 0.0 }, { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" + "type": "sensor.other.gnss", + "id": "gnss", + "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6 } }, { - "type": "sensor.pseudo.markers", - "id": "markers" - }, - { - "type": "vehicle.toyota.prius", - "id": "ego_vehicle", - "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "rgb_front", - "spawn_point": { "x": 0.7, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, - "image_size_x": 480, - "image_size_y": 360, - "fov": 90.0 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 2.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, - "range": 50, - "channels": 64, - "points_per_second": 480000, - "upper_fov": 3.0, - "lower_fov": -27.0, - "rotation_frequency": 20, - "noise_stddev": 0.0 - }, - { - "type": "sensor.other.gnss", - "id": "gnss", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6 }, - "noise_alt_stddev": 0.0, - "noise_lat_stddev": 0.0, - "noise_lon_stddev": 0.0, - "noise_alt_bias": 0.0, - "noise_lat_bias": 0.0, - "noise_lon_bias": 0.0 - }, - { - "type": "sensor.other.imu", - "id": "imu", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, - "noise_accel_stddev_x": 0.0, - "noise_accel_stddev_y": 0.0, - "noise_accel_stddev_z": 0.0, - "noise_gyro_stddev_x": 0.0, - "noise_gyro_stddev_y": 0.0, - "noise_gyro_stddev_z": 0.0, - "noise_gyro_bias_x": 0.0, - "noise_gyro_bias_y": 0.0, - "noise_gyro_bias_z": 0.0 - }, - { - "type": "sensor.other.collision", - "id": "collision", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 0.0 } - }, - { - "type": "sensor.pseudo.tf", - "id": "tf" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.odom", - "id": "odometry" - }, - { - "type": "actor.pseudo.control", - "id": "control" - } - ] + "type": "sensor.other.imu", + "id": "imu", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 1.6, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + } } ] } diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index fc115f9ceaa53..043ba0aadbd63 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -1,6 +1,32 @@ - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulator/carla_autoware/launch/carla_ros.launch.xml b/simulator/carla_autoware/launch/carla_ros.launch.xml deleted file mode 100644 index 1b8b9870f1ddf..0000000000000 --- a/simulator/carla_autoware/launch/carla_ros.launch.xml +++ /dev/null @@ -1,49 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/simulator/carla_autoware/package.xml b/simulator/carla_autoware/package.xml index de94dd7499ea2..fde3c0b16d9cc 100644 --- a/simulator/carla_autoware/package.xml +++ b/simulator/carla_autoware/package.xml @@ -10,16 +10,11 @@ ros2launch ros_compatibility std_msgs - astuff_sensor_msgs autoware_auto_control_msgs autoware_auto_vehicle_msgs - carla_data_provider carla_msgs - datetime geometry_msgs - math nav_msgs - numpy rclpy sensor_msgs sensor_msgs_py diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 82dfb6581d776..223ca5b382dcb 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -1,42 +1,31 @@ from glob import glob import os -ROS_VERSION = int(os.environ["ROS_VERSION"]) - -if ROS_VERSION == 1: - from distutils.core import setup - - from catkin_pkg.python_setup import generate_distutils_setup - - d = generate_distutils_setup(packages=["carla_autoware"], package_dir={"": "src"}) +from setuptools import setup - setup(**d) - -elif ROS_VERSION == 2: - from setuptools import setup - - package_name = "carla_autoware" +ROS_VERSION = int(os.environ["ROS_VERSION"]) - setup( - name=package_name, - version="0.0.0", - packages=[package_name], - data_files=[ - ("share/ament_index/resource_index/packages", ["resource/" + package_name]), - ("share/" + package_name, glob("config/objects.json")), - ("share/" + package_name, ["package.xml"]), - (os.path.join("share", package_name), glob("launch/carla_autoware.launch.xml")), - (os.path.join("share", package_name), glob("launch/carla_ros.launch.xml")), - ], - install_requires=["setuptools"], - zip_safe=True, - maintainer="mradityagio", - maintainer_email="mradityagio@gmail.com", - description="CARLA ROS2 bridge for AUTOWARE", - license="Apache License 2.0", - tests_require=["pytest"], - entry_points={ - "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], - }, - package_dir={"": "src"}, - ) +package_name = "carla_autoware" + +setup( + name=package_name, + version="0.0.0", + packages=[package_name], + data_files=[ + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), + ("share/" + package_name, glob("config/objects.json")), + ("share/" + package_name, ["package.xml"]), + (os.path.join("share", package_name), glob("launch/carla_autoware.launch.xml")), + ], + install_requires=["setuptools"], + zip_safe=True, + maintainer="mradityagio", + maintainer_email="mradityagio@gmail.com", + description="CARLA ROS2 bridge for AUTOWARE", + license="Apache License 2.0", + tests_require=["pytest"], + entry_points={ + "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], + }, + package_dir={"": "src"}, +) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 92fef61976efc..36d2fea5446e4 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -1,157 +1,151 @@ -from autoware_auto_control_msgs.msg import AckermannControlCommand -from autoware_auto_vehicle_msgs.msg import ControlModeReport -from autoware_auto_vehicle_msgs.msg import GearReport -from autoware_auto_vehicle_msgs.msg import SteeringReport -from autoware_auto_vehicle_msgs.msg import VelocityReport -from autoware_perception_msgs.msg import TrafficSignalArray -from carla_msgs.msg import CarlaEgoVehicleControl -from carla_msgs.msg import CarlaEgoVehicleStatus -from geometry_msgs.msg import PoseWithCovarianceStamped -from nav_msgs.msg import Odometry -import rclpy -from rclpy.node import Node - - -class CarlaVehicleInterface(Node): +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.sr/bin/env python + +import signal +import time + +import carla + +from .carla_ros import carla_interface +from .modules.carla_data_provider import CarlaDataProvider +from .modules.carla_data_provider import GameTime +from .modules.carla_wrapper import SensorReceivedNoData +from .modules.carla_wrapper import SensorWrapper + + +class SensorLoop(object): + def __init__(self, role_name): + self.start_game_time = None + self.start_system_time = None + self.sensor = None + self.ego_vehicle = None + self.running = False + self.timestamp_last_run = 0.0 + self.timeout = 20.0 + self.role_name = role_name + + def _stop_loop(self): + self.running = False + + def _tick_sensor(self, timestamp): + if self.timestamp_last_run < timestamp.elapsed_seconds and self.running: + self.timestamp_last_run = timestamp.elapsed_seconds + GameTime.on_carla_tick(timestamp) + CarlaDataProvider.on_carla_tick() + try: + ego_action = self.sensor() + except SensorReceivedNoData as e: + raise RuntimeError(e) + self.ego_vehicle.apply_control(ego_action) + if self.running: + CarlaDataProvider.get_world().tick() + + +class InitializeInterface(object): def __init__(self): - super().__init__("carla_vehicle_interface_node") - self.current_vel = 0.0 - self.target_vel = 0.0 - self.vel_diff = 0.0 - - # Publishes Topics used for AUTOWARE - self.pub_vel_state = self.create_publisher( - VelocityReport, "/vehicle/status/velocity_status", 1 - ) - self.pub_steering_state = self.create_publisher( - SteeringReport, "/vehicle/status/steering_status", 1 - ) - self.pub_ctrl_mode = self.create_publisher( - ControlModeReport, "/vehicle/status/control_mode", 1 - ) - self.pub_gear_state = self.create_publisher(GearReport, "/vehicle/status/gear_status", 1) - self.pub_control = self.create_publisher( - CarlaEgoVehicleControl, "/carla/ego_vehicle/vehicle_control_cmd", 1 - ) - self.pub_traffic_signal_info = self.create_publisher( - TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 - ) - self.pub_pose_with_cov = self.create_publisher( - PoseWithCovarianceStamped, "/sensing/gnss/pose_with_covariance", 1 - ) - - # Subscribe Topics used in Control - self.sub_status = self.create_subscription( - CarlaEgoVehicleStatus, "/carla/ego_vehicle/vehicle_status", self.ego_status_callback, 1 - ) - self.sub_control = self.create_subscription( - AckermannControlCommand, "/control/command/control_cmd", self.control_callback, 1 - ) - self.sub_odom = self.create_subscription( - Odometry, "/carla/ego_vehicle/odometry", self.pose_callback, 1 - ) - - def pose_callback(self, pose_msg): - out_pose_with_cov = PoseWithCovarianceStamped() - out_pose_with_cov.header.frame_id = "map" - out_pose_with_cov.header.stamp = pose_msg.header.stamp - out_pose_with_cov.pose.pose = pose_msg.pose.pose - out_pose_with_cov.pose.covariance = [ - 0.1, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.1, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.1, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - ] - self.pub_pose_with_cov.publish(out_pose_with_cov) - - def ego_status_callback(self, in_status): - """Convert and publish CARLA Ego Vehicle Status to AUTOWARE.""" - out_vel_state = VelocityReport() - out_steering_state = SteeringReport() - out_ctrl_mode = ControlModeReport() - out_gear_state = GearReport() - out_traffic = TrafficSignalArray() - - out_vel_state.header = in_status.header - out_vel_state.header.frame_id = "base_link" - out_vel_state.longitudinal_velocity = in_status.velocity - out_vel_state.lateral_velocity = 0.0 - out_vel_state.heading_rate = 0.0 - self.current_vel = in_status.velocity - - out_steering_state.stamp = in_status.header.stamp - out_steering_state.steering_tire_angle = -in_status.control.steer - - out_gear_state.stamp = in_status.header.stamp - out_gear_state.report = GearReport.DRIVE - - out_ctrl_mode.stamp = in_status.header.stamp - out_ctrl_mode.mode = ControlModeReport.AUTONOMOUS - - self.pub_vel_state.publish(out_vel_state) - self.pub_steering_state.publish(out_steering_state) - self.pub_ctrl_mode.publish(out_ctrl_mode) - self.pub_gear_state.publish(out_gear_state) - self.pub_traffic_signal_info.publish(out_traffic) - - def control_callback(self, in_cmd): - """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" - out_cmd = CarlaEgoVehicleControl() - self.target_vel = abs(in_cmd.longitudinal.speed) - self.vel_diff = self.target_vel - self.current_vel - - if self.vel_diff > 0: - out_cmd.throttle = 0.75 - out_cmd.brake = 0.0 - elif self.vel_diff <= 0.0: - out_cmd.throttle = 0.0 - if self.target_vel <= 0.0: - out_cmd.brake = 0.75 - elif self.vel_diff > -1: - out_cmd.brake = 0.0 + self.interface = carla_interface() + self.param_ = self.interface.get_param() + self.world = None + self.sensor_wrapper = None + self.ego_vehicle = None + + # Parameter for Initializing Carla World + self.local_host = self.param_["host"] + self.port = self.param_["port"] + self.timeout = self.param_["timeout"] + self.sync_mode = self.param_["sync_mode"] + self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] + self.map_name = self.param_["map_name"] + self.agent_role_name = self.param_["ego_vehicle_role_name"] + self.vehicle_type = self.param_["vehicle_type"] + self.spawn_point = self.param_["spawn_point"] + + def load_world(self): + client = carla.Client(self.local_host, self.port) + client.set_timeout(self.timeout) + client.load_world(self.map_name) + self.world = client.get_world() + if self.world is not None: + settings = self.world.get_settings() + settings.fixed_delta_seconds = self.fixed_delta_seconds + settings.synchronous_mode = self.sync_mode + self.world.apply_settings(settings) + CarlaDataProvider.set_world(self.world) + CarlaDataProvider.set_client(client) + spawn_point = carla.Transform() + spawn_point = carla.Transform() + point_items = self.spawn_point.split(",") + randomize = False + if len(point_items) == 6: + spawn_point.location.x = float(point_items[0]) + spawn_point.location.y = float(point_items[1]) + spawn_point.location.z = float(point_items[2]) + 2 + spawn_point.rotation.roll = float(point_items[3]) + spawn_point.rotation.pitch = float(point_items[4]) + spawn_point.rotation.yaw = float(point_items[5]) else: - out_cmd.brake = 0.01 - - out_cmd.steer = -in_cmd.lateral.steering_tire_angle - self.pub_control.publish(out_cmd) - - -def main(args=None): - rclpy.init() - node = CarlaVehicleInterface() - rclpy.spin(node) + randomize = True + CarlaDataProvider.request_new_actor( + self.vehicle_type, spawn_point, self.agent_role_name, random_location=randomize + ) + + self.sensor_wrapper = SensorWrapper(self.interface) + self.ego_vehicle = CarlaDataProvider.get_actor_by_name(self.agent_role_name) + self.sensor_wrapper.setup_sensors(self.ego_vehicle, False) + + else: + print("Carla Interface Couldn't find the world, Carla is not Running") + + def run_bridge(self): + self.bridge_loop = SensorLoop(self.agent_role_name) + self.bridge_loop.sensor = self.sensor_wrapper + self.bridge_loop.ego_vehicle = self.ego_vehicle + self.bridge_loop.start_system_time = time.time() + self.bridge_loop.start_game_time = GameTime.get_time() + self.bridge_loop.role_name = self.agent_role_name + self.bridge_loop.running = True + while self.bridge_loop.running: + timestamp = None + world = CarlaDataProvider.get_world() + if world: + snapshot = world.get_snapshot() + if snapshot: + timestamp = snapshot.timestamp + if timestamp: + self.bridge_loop._tick_sensor(timestamp) + + def _stop_loop(self, signum, frame): + self.bridge_loop._stop_loop() + + def _cleanup(self): + self.sensor_wrapper.cleanup() + CarlaDataProvider.cleanup() + if self.ego_vehicle: + self.ego_vehicle.destroy() + self.ego_vehicle = None + + if self.interface: + self.interface = None + + +def main(): + carla_bridge = InitializeInterface() + carla_bridge.load_world() + stop_bridge = signal.signal(signal.SIGINT, carla_bridge._stop_loop) + carla_bridge.run_bridge() + signal.signal(signal.SIGINT, stop_bridge) + carla_bridge._cleanup() if __name__ == "__main__": diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py new file mode 100644 index 0000000000000..c3037db4d25c1 --- /dev/null +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -0,0 +1,420 @@ +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.sr/bin/env python + +import json +import logging +import math +import threading + +from autoware_auto_control_msgs.msg import AckermannControlCommand +from autoware_auto_vehicle_msgs.msg import ControlModeReport +from autoware_auto_vehicle_msgs.msg import GearReport +from autoware_auto_vehicle_msgs.msg import SteeringReport +from autoware_auto_vehicle_msgs.msg import VelocityReport +from autoware_perception_msgs.msg import TrafficSignalArray +from builtin_interfaces.msg import Time +import carla +from cv_bridge import CvBridge +from geometry_msgs.msg import Pose +from geometry_msgs.msg import PoseWithCovarianceStamped +import numpy +import rclpy +from rosgraph_msgs.msg import Clock +from sensor_msgs.msg import CameraInfo +from sensor_msgs.msg import Image +from sensor_msgs.msg import Imu +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from std_msgs.msg import Header +from transforms3d.euler import euler2quat + +from .modules.carla_data_provider import CarlaDataProvider +from .modules.carla_data_provider import GameTime +from .modules.carla_data_provider import datetime +from .modules.carla_utils import carla_location_to_ros_point +from .modules.carla_utils import carla_rotation_to_ros_quaternion +from .modules.carla_utils import create_cloud +from .modules.carla_wrapper import SensorInterface + + +class carla_interface(object): + def __init__(self): + self.sensor_interface = SensorInterface() + self.setup() + + def setup(self): + self.timestamp = None + self.channels = 0 + self.id_to_sensor_type_map = {} + self.id_to_camera_info_map = {} + self.cv_bridge = CvBridge() + self.first_ = True + self.sensor_frequencies = {"lidar": 11, "camera": 11, "imu": 50, "status": 50, "pose": 2} + self.publish_prev_times = { + sensor: datetime.datetime.now() for sensor in self.sensor_frequencies + } + + # initialize ros2 node + rclpy.init(args=None) + self.ros2_node = rclpy.create_node("carla_interface") + self.logger = logging.getLogger("log") + self.parameters = { + "host": rclpy.Parameter.Type.STRING, + "port": rclpy.Parameter.Type.INTEGER, + "sync_mode": rclpy.Parameter.Type.BOOL, + "timeout": rclpy.Parameter.Type.INTEGER, + "fixed_delta_seconds": rclpy.Parameter.Type.DOUBLE, + "map_name": rclpy.Parameter.Type.STRING, + "ego_vehicle_role_name": rclpy.Parameter.Type.STRING, + "spawn_point": rclpy.Parameter.Type.STRING, + "vehicle_type": rclpy.Parameter.Type.STRING, + "objects_definition_file": rclpy.Parameter.Type.STRING, + } + self.param_values = {} + for param_name, param_type in self.parameters.items(): + self.ros2_node.declare_parameter(param_name, param_type) + self.param_values[param_name] = self.ros2_node.get_parameter(param_name).value + + # Publish clock + self.clock_publisher = self.ros2_node.create_publisher(Clock, "/clock", 10) + obj_clock = Clock() + obj_clock.clock = Time(sec=0) + self.clock_publisher.publish(obj_clock) + + # Sensor Config (Edit your sensor here) + self.sensors = json.load(open(self.param_values["objects_definition_file"])) + + # Subscribing Autoware Control messages and converting to CARLA control + self.sub_control = self.ros2_node.create_subscription( + AckermannControlCommand, "/control/command/control_cmd", self.control_callback, 1 + ) + self.current_control = carla.VehicleControl() + + # Direct data publishing from CARLA for Autoware + self.pub_pose_with_cov = self.ros2_node.create_publisher( + PoseWithCovarianceStamped, "/sensing/gnss/pose_with_covariance", 1 + ) + self.pub_traffic_signal_info = self.ros2_node.create_publisher( + TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 + ) + self.pub_vel_state = self.ros2_node.create_publisher( + VelocityReport, "/vehicle/status/velocity_status", 1 + ) + self.pub_steering_state = self.ros2_node.create_publisher( + SteeringReport, "/vehicle/status/steering_status", 1 + ) + self.pub_ctrl_mode = self.ros2_node.create_publisher( + ControlModeReport, "/vehicle/status/control_mode", 1 + ) + self.pub_gear_state = self.ros2_node.create_publisher( + GearReport, "/vehicle/status/gear_status", 1 + ) + + # Create Publisher for each Physical Sensors + for sensor in self.sensors["sensors"]: + self.id_to_sensor_type_map[sensor["id"]] = sensor["type"] + if sensor["type"] == "sensor.camera.rgb": + self.pub_camera = self.ros2_node.create_publisher( + Image, "/sensing/camera/traffic_light/image_raw", 1 + ) + self.pub_camera_info = self.ros2_node.create_publisher( + CameraInfo, "/sensing/camera/traffic_light/camera_info", 1 + ) + elif sensor["type"] == "sensor.lidar.ray_cast": + self.pub_lidar = self.ros2_node.create_publisher( + PointCloud2, "/sensing/lidar/top/outlier_filtered/pointcloud", 10 + ) + elif sensor["type"] == "sensor.other.imu": + self.pub_imu = self.ros2_node.create_publisher( + Imu, "/sensing/imu/tamagawa/imu_raw", 1 + ) + else: + self.logger.info("No Publisher for this Sensor") + pass + + self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) + self.spin_thread.start() + + def __call__(self): + input_data = self.sensor_interface.get_data() + timestamp = GameTime.get_time() + control = self.run_step(input_data, timestamp) + control.manual_gear_shift = False + return control + + def get_param(self): + return self.param_values + + def control_callback(self, in_cmd): + """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" + out_cmd = carla.VehicleControl() + self.target_vel = abs(in_cmd.longitudinal.speed) + self.vel_diff = self.target_vel - self.current_vel + + if self.vel_diff > 0: + out_cmd.throttle = 0.75 + out_cmd.brake = 0.0 + elif self.vel_diff <= 0.0: + out_cmd.throttle = 0.0 + if self.target_vel <= 0.0: + out_cmd.brake = 0.75 + elif self.vel_diff > -1: + out_cmd.brake = 0.0 + else: + out_cmd.brake = 0.01 + + out_cmd.steer = -in_cmd.lateral.steering_tire_angle + self.current_control = out_cmd + + def checkFrequency(self, sensor): + time_delta = ( + datetime.datetime.now() - self.publish_prev_times[sensor] + ).microseconds / 1000000.0 + if 1.0 / time_delta >= self.sensor_frequencies[sensor]: + return True + return False + + def get_msg_header(self, frame_id): + """Obtain and modify ROS message header.""" + header = Header() + header.frame_id = frame_id + seconds = int(self.timestamp) + nanoseconds = int((self.timestamp - int(self.timestamp)) * 1000000000.0) + header.stamp = Time(sec=seconds, nanosec=nanoseconds) + return header + + def lidar(self, carla_lidar_measurement): + """Transform the a received lidar measurement into a ROS point cloud message.""" + if self.checkFrequency("lidar"): + return + self.publish_prev_times["lidar"] = datetime.datetime.now() + + header = self.get_msg_header(frame_id="velodyne_top") + fields = [ + PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), + PointField(name="intensity", offset=12, datatype=PointField.FLOAT32, count=1), + PointField(name="ring", offset=16, datatype=PointField.UINT16, count=1), + ] + + lidar_data = numpy.fromstring(bytes(carla_lidar_measurement.raw_data), dtype=numpy.float32) + lidar_data = numpy.reshape(lidar_data, (int(lidar_data.shape[0] / 4), 4)) + + ring = numpy.empty((0, 1), object) + self.channels = self.sensors["sensors"] + + for i in range(self.channels[1]["channels"]): + current_ring_points_count = carla_lidar_measurement.get_point_count(i) + ring = numpy.vstack((ring, numpy.full((current_ring_points_count, 1), i))) + + lidar_data = numpy.hstack((lidar_data, ring)) + + lidar_data[:, 1] *= -1 + point_cloud_msg = create_cloud(header, fields, lidar_data) + self.pub_lidar.publish(point_cloud_msg) + + def pose(self): + """Transform odometry data to Pose and publish Pose with Covariance message.""" + if self.checkFrequency("pose"): + return + self.publish_prev_times["pose"] = datetime.datetime.now() + + header = self.get_msg_header(frame_id="map") + ego_ = CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) + + out_pose_with_cov = PoseWithCovarianceStamped() + pose_carla = Pose() + pose_carla.position = carla_location_to_ros_point( + CarlaDataProvider.get_transform(ego_).location + ) + pose_carla.orientation = carla_rotation_to_ros_quaternion( + CarlaDataProvider.get_transform(ego_).rotation + ) + out_pose_with_cov.header = header + out_pose_with_cov.pose.pose = pose_carla + out_pose_with_cov.pose.covariance = [ + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.1, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + ] + self.pub_pose_with_cov.publish(out_pose_with_cov) + + def _build_camera_info(self, camera_actor): + """Build camera info.""" + camera_info = CameraInfo() + camera_info.width = camera_actor.width + camera_info.height = camera_actor.height + camera_info.distortion_model = "plumb_bob" + cx = camera_info.width / 2.0 + cy = camera_info.height / 2.0 + fx = camera_info.width / (2.0 * math.tan(camera_actor.fov * math.pi / 360.0)) + fy = fx + camera_info.k = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] + camera_info.d = [0.0, 0.0, 0.0, 0.0, 0.0] + camera_info.r = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] + camera_info.p = [fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0] + self._camera_info = camera_info + + def camera(self, carla_camera_data): + """Transform the received carla camera data into a ROS image and info message and publish.""" + while self.first_: + self._camera_info_ = self._build_camera_info(carla_camera_data) + self.first_ = False + + if self.checkFrequency("camera"): + return + self.publish_prev_times["camera"] = datetime.datetime.now() + + image_data_array = numpy.ndarray( + shape=(carla_camera_data.height, carla_camera_data.width, 4), + dtype=numpy.uint8, + buffer=carla_camera_data.raw_data, + ) + img_msg = self.cv_bridge.cv2_to_imgmsg(image_data_array, encoding="bgra8") + img_msg.header = self.get_msg_header(frame_id="traffic_light_left_camera/camera_link") + cam_info = self._camera_info + cam_info.header = img_msg.header + self.pub_camera_info.publish(cam_info) + self.pub_camera.publish(img_msg) + + def imu(self, carla_imu_measurement): + """Transform a received imu measurement into a ROS Imu message and publish Imu message.""" + if self.checkFrequency("imu"): + return + self.publish_prev_times["imu"] = datetime.datetime.now() + + imu_msg = Imu() + imu_msg.header = self.get_msg_header(frame_id="tamagawa/imu_link") + imu_msg.angular_velocity.x = -carla_imu_measurement.gyroscope.x + imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y + imu_msg.angular_velocity.z = -carla_imu_measurement.gyroscope.z + + imu_msg.linear_acceleration.x = carla_imu_measurement.accelerometer.x + imu_msg.linear_acceleration.y = -carla_imu_measurement.accelerometer.y + imu_msg.linear_acceleration.z = carla_imu_measurement.accelerometer.z + + roll = math.radians(carla_imu_measurement.transform.rotation.roll) + pitch = -math.radians(carla_imu_measurement.transform.rotation.pitch) + yaw = -math.radians(carla_imu_measurement.transform.rotation.yaw) + + quat = euler2quat(roll, pitch, yaw) + imu_msg.orientation.w = quat[0] + imu_msg.orientation.x = quat[1] + imu_msg.orientation.y = quat[2] + imu_msg.orientation.z = quat[3] + + self.pub_imu.publish(imu_msg) + + def ego_status(self): + """Publish ego vehicle status.""" + if self.checkFrequency("status"): + return + self.publish_prev_times["status"] = datetime.datetime.now() + + in_status = CarlaDataProvider.get_actor_by_name( + self.param_values["ego_vehicle_role_name"] + ).get_control() + velocity = CarlaDataProvider.get_actor_by_name( + self.param_values["ego_vehicle_role_name"] + ).get_velocity() + vel_np = numpy.array([velocity.x, velocity.y, velocity.z]) + orientation = numpy.array([1, 1, 0]) + in_vel_state = numpy.abs(numpy.dot(vel_np, orientation)) + self.current_vel = in_vel_state + + out_vel_state = VelocityReport() + out_steering_state = SteeringReport() + out_ctrl_mode = ControlModeReport() + out_gear_state = GearReport() + out_traffic = TrafficSignalArray() + + out_vel_state.header = self.get_msg_header(frame_id="base_link") + out_vel_state.longitudinal_velocity = in_vel_state + out_vel_state.lateral_velocity = 0.0 + out_vel_state.heading_rate = 0.0 + + out_steering_state.stamp = out_vel_state.header.stamp + out_steering_state.steering_tire_angle = -in_status.steer + + out_gear_state.stamp = out_vel_state.header.stamp + out_gear_state.report = GearReport.DRIVE + + out_ctrl_mode.stamp = out_vel_state.header.stamp + out_ctrl_mode.mode = ControlModeReport.AUTONOMOUS + + self.pub_vel_state.publish(out_vel_state) + self.pub_steering_state.publish(out_steering_state) + self.pub_ctrl_mode.publish(out_ctrl_mode) + self.pub_gear_state.publish(out_gear_state) + self.pub_traffic_signal_info.publish(out_traffic) + + def run_step(self, input_data, timestamp): + self.timestamp = timestamp + seconds = int(self.timestamp) + nanoseconds = int((self.timestamp - int(self.timestamp)) * 1000000000.0) + obj_clock = Clock() + obj_clock.clock = Time(sec=seconds, nanosec=nanoseconds) + self.clock_publisher.publish(obj_clock) + + # publish data of all sensors + for key, data in input_data.items(): + sensor_type = self.id_to_sensor_type_map[key] + if sensor_type == "sensor.camera.rgb": + self.camera(data[1]) + elif sensor_type == "sensor.other.gnss": + self.pose() + elif sensor_type == "sensor.lidar.ray_cast": + self.lidar(data[1]) + elif sensor_type == "sensor.other.imu": + self.imu(data[1]) + else: + self.logger.info("No Publisher for [{key}] Sensor") + + # Publish ego vehicle status + self.ego_status() + return self.current_control diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py new file mode 100644 index 0000000000000..4e606e336a9f9 --- /dev/null +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -0,0 +1,853 @@ +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.sr/bin/env python + +############################################################## +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +############################################################## + +"""Modified CARLA Data Provider from CARLA scenario runner.""" + +from __future__ import print_function + +import datetime +import math +import re +import threading + +import carla +from numpy import random +from six import iteritems + + +def calculate_velocity(actor): + """Calculate the velocity of a actor.""" + velocity_squared = actor.get_velocity().x ** 2 + velocity_squared += actor.get_velocity().y ** 2 + return math.sqrt(velocity_squared) + + +class CarlaDataProvider(object): # pylint: disable=too-many-public-methods + _actor_velocity_map = {} + _actor_location_map = {} + _actor_transform_map = {} + _traffic_light_map = {} + _carla_actor_pool = {} + _global_osc_parameters = {} + _client = None + _world = None + _map = None + _sync_flag = False + _spawn_points = None + _spawn_index = 0 + _blueprint_library = None + _all_actors = None + _ego_vehicle_route = None + _traffic_manager_port = 8000 + _random_seed = 2000 + _rng = random.RandomState(_random_seed) + _local_planner = None + _runtime_init_flag = False + _lock = threading.Lock() + + @staticmethod + def set_local_planner(plan): + CarlaDataProvider._local_planner = plan + + @staticmethod + def get_local_planner(): + return CarlaDataProvider._local_planner + + @staticmethod + def register_actor(actor, transform=None): + """Add new actor to dictionaries.""" + with CarlaDataProvider._lock: + if actor in CarlaDataProvider._actor_velocity_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id) + ) + else: + CarlaDataProvider._actor_velocity_map[actor] = 0.0 + if actor in CarlaDataProvider._actor_location_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id) + ) + elif transform: + CarlaDataProvider._actor_location_map[actor] = transform.location + else: + CarlaDataProvider._actor_location_map[actor] = None + + if actor in CarlaDataProvider._actor_transform_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id) + ) + else: + CarlaDataProvider._actor_transform_map[actor] = transform + + @staticmethod + def update_osc_global_params(parameters): + """Updates/initializes global osc parameters.""" + CarlaDataProvider._global_osc_parameters.update(parameters) + + @staticmethod + def get_osc_global_param_value(ref): + """Return updated global osc parameter value.""" + return CarlaDataProvider._global_osc_parameters.get(ref.replace("$", "")) + + @staticmethod + def register_actors(actors, transforms=None): + """Add new set of actors to dictionaries.""" + if transforms is None: + transforms = [None] * len(actors) + + for actor, transform in zip(actors, transforms): + CarlaDataProvider.register_actor(actor, transform) + + @staticmethod + def on_carla_tick(): + with CarlaDataProvider._lock: + for actor in CarlaDataProvider._actor_velocity_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_velocity_map[actor] = calculate_velocity(actor) + + for actor in CarlaDataProvider._actor_location_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_location_map[actor] = actor.get_location() + + for actor in CarlaDataProvider._actor_transform_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_transform_map[actor] = actor.get_transform() + + world = CarlaDataProvider._world + if world is None: + print("WARNING: CarlaDataProvider couldn't find the world") + + CarlaDataProvider._all_actors = None + + @staticmethod + def get_velocity(actor): + """Return the absolute velocity for the given actor.""" + for key in CarlaDataProvider._actor_velocity_map: + if key.id == actor.id: + return CarlaDataProvider._actor_velocity_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print("{}.get_velocity: {} not found!".format(__name__, actor)) + return 0.0 + + @staticmethod + def get_location(actor): + """Return the location for the given actor.""" + for key in CarlaDataProvider._actor_location_map: + if key.id == actor.id: + return CarlaDataProvider._actor_location_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print("{}.get_location: {} not found!".format(__name__, actor)) + return None + + @staticmethod + def get_transform(actor): + """Return the transform for the given actor.""" + for key in CarlaDataProvider._actor_transform_map: + if key.id == actor.id: + # The velocity location information is the entire behavior tree updated every tick + # The ego vehicle is created before the behavior tree tick, so exception handling needs to be added + if CarlaDataProvider._actor_transform_map[key] is None: + return actor.get_transform() + return CarlaDataProvider._actor_transform_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print("{}.get_transform: {} not found!".format(__name__, actor)) + return None + + @staticmethod + def get_random_seed(): + """Return the random seed.""" + return CarlaDataProvider._rng + + @staticmethod + def set_client(client): + """Set the CARLA client.""" + CarlaDataProvider._client = client + + @staticmethod + def get_client(): + """Get the CARLA client.""" + return CarlaDataProvider._client + + @staticmethod + def set_world(world): + """Set the world and world settings.""" + CarlaDataProvider._world = world + CarlaDataProvider._sync_flag = world.get_settings().synchronous_mode + CarlaDataProvider._map = world.get_map() + CarlaDataProvider._blueprint_library = world.get_blueprint_library() + CarlaDataProvider.generate_spawn_points() + CarlaDataProvider.prepare_map() + + @staticmethod + def get_world(): + """Return world.""" + return CarlaDataProvider._world + + @staticmethod + def get_all_actors(): + """Return all the world actors.""" + if CarlaDataProvider._all_actors: + return CarlaDataProvider._all_actors + + CarlaDataProvider._all_actors = CarlaDataProvider._world.get_actors() + return CarlaDataProvider._all_actors + + @staticmethod + def set_runtime_init_mode(flag): + """Set the runtime init mode.""" + CarlaDataProvider._runtime_init_flag = flag + + @staticmethod + def is_runtime_init_mode(): + """Return true if runtime init mode is used.""" + return CarlaDataProvider._runtime_init_flag + + @staticmethod + def find_weather_presets(): + """Get weather presets from CARLA.""" + rgx = re.compile(".+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)") + + def format_name(x): + return " ".join(m.group(0) for m in rgx.finditer(x)) + + presets = [x for x in dir(carla.WeatherParameters) if re.match("[A-Z].+", x)] + return [(getattr(carla.WeatherParameters, x), format_name(x)) for x in presets] + + @staticmethod + def prepare_map(): + """Set the current map and loads all traffic lights for this map to_traffic_light_map.""" + if CarlaDataProvider._map is None: + CarlaDataProvider._map = CarlaDataProvider._world.get_map() + + # Parse all traffic lights + CarlaDataProvider._traffic_light_map.clear() + for traffic_light in CarlaDataProvider._world.get_actors().filter("*traffic_light*"): + if traffic_light not in list(CarlaDataProvider._traffic_light_map): + CarlaDataProvider._traffic_light_map[traffic_light] = traffic_light.get_transform() + else: + raise KeyError( + "Traffic light '{}' already registered. Cannot register twice!".format( + traffic_light.id + ) + ) + + @staticmethod + def generate_spawn_points(): + """Generate spawn points for the current map.""" + spawn_points = list(CarlaDataProvider.get_map(CarlaDataProvider._world).get_spawn_points()) + CarlaDataProvider._rng.shuffle(spawn_points) + CarlaDataProvider._spawn_points = spawn_points + CarlaDataProvider._spawn_index = 0 + + @staticmethod + def check_road_length(wp, length: float): + waypoint_separation = 5 + + cur_len = 0 + road_id, lane_id = wp.road_id, wp.lane_id + while True: + wps = wp.next(waypoint_separation) + # The same roadid and laneid,judged to be in the same section to be tested + next_wp = None + for p in wps: + if p.road_id == road_id and p.lane_id == lane_id: + next_wp = p + break + if next_wp is None: + break + cur_len += waypoint_separation + if cur_len >= length: + return True + wp = next_wp + return False + + @staticmethod + def get_road_lanes(wp): + if wp.is_junction: + return [] + # find the most left lane's waypoint + + lane_id_set = set() + pre_left = wp + while wp and wp.lane_type == carla.LaneType.Driving: + if wp.lane_id in lane_id_set: + break + lane_id_set.add(wp.lane_id) + + # carla bug: get_left_lane Return error,and never Return none. It's a infinite loop. + pre_left = wp + wp = wp.get_left_lane() + + # # Store data from the left lane to the right lane + # # list, key=laneid, value=waypoint + lane_list = [] + lane_id_set.clear() + wp = pre_left + while wp and wp.lane_type == carla.LaneType.Driving: + if wp.lane_id in lane_id_set: + break + lane_id_set.add(wp.lane_id) + + lane_list.append(wp) + + # carla bug: Return error, never return none, endless loop + wp = wp.get_right_lane() + + return lane_list + + @staticmethod + def get_road_lane_cnt(wp): + lanes = CarlaDataProvider.get_road_lanes(wp) + return len(lanes) + + @staticmethod + def get_waypoint_by_laneid(lane_num: int): + if CarlaDataProvider._spawn_points is None: + CarlaDataProvider.generate_spawn_points() + + if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): + print("No more spawn points to use") + return None + else: + pos = CarlaDataProvider._spawn_points[ + CarlaDataProvider._spawn_index + ] # pylint: disable=unsubscriptable-object + CarlaDataProvider._spawn_index += 1 + wp = CarlaDataProvider.get_map().get_waypoint( + pos.location, project_to_road=True, lane_type=carla.LaneType.Driving + ) + + road_lanes = CarlaDataProvider.get_road_lanes(wp) + + lane = int(float(lane_num)) + if lane > len(road_lanes): + return None + else: + return road_lanes[lane - 1] + + @staticmethod + def create_blueprint( + model, rolename="scenario", color=None, actor_category="car", attribute_filter=None + ): + """Set up the blueprint of an actor given its model and other relevant parameters.""" + + def check_attribute_value(blueprint, name, value): + """Check if the blueprint has that attribute with that value.""" + if not blueprint.has_attribute(name): + return False + + attribute_type = blueprint.get_attribute(key).type + if attribute_type == carla.ActorAttributeType.Bool: + return blueprint.get_attribute(name).as_bool() == value + elif attribute_type == carla.ActorAttributeType.Int: + return blueprint.get_attribute(name).as_int() == value + elif attribute_type == carla.ActorAttributeType.Float: + return blueprint.get_attribute(name).as_float() == value + elif attribute_type == carla.ActorAttributeType.String: + return blueprint.get_attribute(name).as_str() == value + + return False + + _actor_blueprint_categories = { + "car": "vehicle.tesla.model3", + "van": "vehicle.volkswagen.t2", + "truck": "vehicle.carlamotors.carlacola", + "trailer": "", + "semitrailer": "", + "bus": "vehicle.volkswagen.t2", + "motorbike": "vehicle.kawasaki.ninja", + "bicycle": "vehicle.diamondback.century", + "train": "", + "tram": "", + "pedestrian": "walker.pedestrian.0001", + } + + # Set the model + try: + blueprints = CarlaDataProvider._blueprint_library.filter(model) + if attribute_filter is not None: + for key, value in attribute_filter.items(): + blueprints = [x for x in blueprints if check_attribute_value(x, key, value)] + + blueprint = CarlaDataProvider._rng.choice(blueprints) + except ValueError: + # The model is not part of the blueprint library. Let's take a default one for the given category + bp_filter = "vehicle.*" + new_model = _actor_blueprint_categories[actor_category] + if new_model != "": + bp_filter = new_model + print( + "WARNING: Actor model {} not available. Using instead {}".format(model, new_model) + ) + blueprint = CarlaDataProvider._rng.choice( + CarlaDataProvider._blueprint_library.filter(bp_filter) + ) + + # Set the color + if color: + if not blueprint.has_attribute("color"): + print( + "WARNING: Cannot set Color ({}) for actor {} due to missing blueprint attribute".format( + color, blueprint.id + ) + ) + else: + default_color_rgba = blueprint.get_attribute("color").as_color() + default_color = "({}, {}, {})".format( + default_color_rgba.r, default_color_rgba.g, default_color_rgba.b + ) + try: + blueprint.set_attribute("color", color) + except ValueError: + # Color can't be set for this vehicle + print( + "WARNING: Color ({}) cannot be set for actor {}. Using instead: ({})".format( + color, blueprint.id, default_color + ) + ) + blueprint.set_attribute("color", default_color) + else: + if blueprint.has_attribute("color") and rolename != "hero": + color = CarlaDataProvider._rng.choice( + blueprint.get_attribute("color").recommended_values + ) + blueprint.set_attribute("color", color) + + # Make pedestrians mortal + if blueprint.has_attribute("is_invincible"): + blueprint.set_attribute("is_invincible", "false") + + # Set the rolename + if blueprint.has_attribute("role_name"): + blueprint.set_attribute("role_name", rolename) + + return blueprint + + @staticmethod + def handle_actor_batch(batch, tick=True): + """Forward a CARLA command batch to spawn actors to CARLA, and gather the responses.""" + sync_mode = CarlaDataProvider.is_sync_mode() + actors = [] + + if CarlaDataProvider._client: + responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode and tick) + else: + raise ValueError("class member 'client'' not initialized yet") + + # Wait (or not) for the actors to be spawned properly before we do anything + if not tick: + pass + elif CarlaDataProvider.is_runtime_init_mode(): + CarlaDataProvider._world.wait_for_tick() + elif sync_mode: + CarlaDataProvider._world.tick() + else: + CarlaDataProvider._world.wait_for_tick() + + actor_ids = [r.actor_id for r in responses if not r.error] + for r in responses: + if r.error: + print("WARNING: Not all actors were spawned") + break + actors = list(CarlaDataProvider._world.get_actors(actor_ids)) + return actors + + @staticmethod + def request_new_actor( + model, + spawn_point, + rolename="scenario", + autopilot=False, + random_location=False, + color=None, + actor_category="car", + attribute_filter=None, + tick=True, + ): + """Create a new actor, returning it if successful (None otherwise).""" + blueprint = CarlaDataProvider.create_blueprint( + model, rolename, color, actor_category, attribute_filter + ) + + if random_location: + actor = None + while not actor: + spawn_point = CarlaDataProvider._rng.choice(CarlaDataProvider._spawn_points) + actor = CarlaDataProvider._world.try_spawn_actor(blueprint, spawn_point) + + else: + # For non prop models, slightly lift the actor to avoid collisions with the ground + z_offset = 0.2 if "prop" not in model else 0 + + # DO NOT USE spawn_point directly, as this will modify spawn_point permanently + _spawn_point = carla.Transform(carla.Location(), spawn_point.rotation) + _spawn_point.location.x = spawn_point.location.x + _spawn_point.location.y = spawn_point.location.y + _spawn_point.location.z = spawn_point.location.z + z_offset + actor = CarlaDataProvider._world.try_spawn_actor(blueprint, _spawn_point) + + if actor is None: + print( + "WARNING: Cannot spawn actor {} at position {}".format(model, spawn_point.location) + ) + return None + + # De/activate the autopilot of the actor if it belongs to vehicle + if autopilot: + if isinstance(actor, carla.Vehicle): + actor.set_autopilot(autopilot, CarlaDataProvider._traffic_manager_port) + else: + print("WARNING: Tried to set the autopilot of a non vehicle actor") + + # Wait for the actor to be spawned properly before we do anything + if not tick: + pass + elif CarlaDataProvider.is_runtime_init_mode(): + CarlaDataProvider._world.wait_for_tick() + elif CarlaDataProvider.is_sync_mode(): + CarlaDataProvider._world.tick() + else: + CarlaDataProvider._world.wait_for_tick() + + if actor is None: + return None + + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor, spawn_point) + return actor + + @staticmethod + def request_new_actors(actor_list, attribute_filter=None, tick=True): + """Series of actor in batch. If this was successful, the new actors are returned, None otherwise.""" + SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name + PhysicsCommand = carla.command.SetSimulatePhysics # pylint: disable=invalid-name + FutureActor = carla.command.FutureActor # pylint: disable=invalid-name + ApplyTransform = carla.command.ApplyTransform # pylint: disable=invalid-name + SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name + SetVehicleLightState = carla.command.SetVehicleLightState # pylint: disable=invalid-name + + batch = [] + actors = [] + + CarlaDataProvider.generate_spawn_points() + + for actor in actor_list: + # Get the blueprint + blueprint = CarlaDataProvider.create_blueprint( + actor.model, actor.rolename, actor.color, actor.category, attribute_filter + ) + + # Get the spawn point + transform = actor.transform + if not transform: + continue + if actor.random_location: + if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): + print("No more spawn points to use") + break + else: + _spawn_point = CarlaDataProvider._spawn_points[ + CarlaDataProvider._spawn_index + ] # pylint: disable=unsubscriptable-object + CarlaDataProvider._spawn_index += 1 + + else: + _spawn_point = carla.Transform() + _spawn_point.rotation = transform.rotation + _spawn_point.location.x = transform.location.x + _spawn_point.location.y = transform.location.y + if blueprint.has_tag("walker"): + # On imported OpenDRIVE maps, spawning of pedestrians can fail. + # By increasing the z-value the chances of success are increased. + map_name = CarlaDataProvider._map.name.split("/")[-1] + if not map_name.startswith("OpenDrive"): + _spawn_point.location.z = transform.location.z + 0.2 + else: + _spawn_point.location.z = transform.location.z + 0.8 + else: + _spawn_point.location.z = transform.location.z + 0.2 + + # Get the command + command = SpawnActor(blueprint, _spawn_point) + command.then( + SetAutopilot(FutureActor, actor.autopilot, CarlaDataProvider._traffic_manager_port) + ) + + if ( + actor.args is not None + and "physics" in actor.args + and actor.args["physics"] == "off" + ): + command.then(ApplyTransform(FutureActor, _spawn_point)).then( + PhysicsCommand(FutureActor, False) + ) + elif actor.category == "misc": + command.then(PhysicsCommand(FutureActor, True)) + if actor.args is not None and "lights" in actor.args and actor.args["lights"] == "on": + command.then(SetVehicleLightState(FutureActor, carla.VehicleLightState.All)) + + batch.append(command) + + actors = CarlaDataProvider.handle_actor_batch(batch, tick) + + if not actors: + return None + + for actor in actors: + if actor is None: + continue + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor, _spawn_point) + + return actors + + @staticmethod + def request_new_batch_actors( + model, + amount, + spawn_points, + autopilot=False, + random_location=False, + rolename="scenario", + attribute_filter=None, + tick=True, + ): + SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name + SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name + FutureActor = carla.command.FutureActor # pylint: disable=invalid-name + + CarlaDataProvider.generate_spawn_points() + + batch = [] + + for i in range(amount): + # Get vehicle by model + blueprint = CarlaDataProvider.create_blueprint( + model, rolename, attribute_filter=attribute_filter + ) + + if random_location: + if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): + print( + "No more spawn points to use. Spawned {} actors out of {}".format( + i + 1, amount + ) + ) + break + else: + spawn_point = CarlaDataProvider._spawn_points[ + CarlaDataProvider._spawn_index + ] # pylint: disable=unsubscriptable-object + CarlaDataProvider._spawn_index += 1 + else: + try: + spawn_point = spawn_points[i] + except IndexError: + print("The amount of spawn points is lower than the amount of vehicles spawned") + break + + if spawn_point: + batch.append( + SpawnActor(blueprint, spawn_point).then( + SetAutopilot( + FutureActor, autopilot, CarlaDataProvider._traffic_manager_port + ) + ) + ) + + actors = CarlaDataProvider.handle_actor_batch(batch, tick) + for actor in actors: + if actor is None: + continue + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor, spawn_point) + + return actors + + @staticmethod + def get_actors(): + """Return list of actors and their ids.""" + return iteritems(CarlaDataProvider._carla_actor_pool) + + @staticmethod + def actor_id_exists(actor_id): + """Check if a certain id is still at the simulation.""" + if actor_id in CarlaDataProvider._carla_actor_pool: + return True + + return False + + @staticmethod + def get_hero_actor(): + """Get the actor object of the hero actor if it exists, Return none otherwise.""" + for actor_id in CarlaDataProvider._carla_actor_pool: + if CarlaDataProvider._carla_actor_pool[actor_id].attributes["role_name"] == "hero": + return CarlaDataProvider._carla_actor_pool[actor_id] + return None + + @staticmethod + def get_actor_by_id(actor_id): + """Get an actor from the pool by using its ID. If the actor does not exist, None is returned.""" + print(CarlaDataProvider._carla_actor_pool) + if actor_id in CarlaDataProvider._carla_actor_pool: + return CarlaDataProvider._carla_actor_pool[actor_id] + + print("Non-existing actor id {}".format(actor_id)) + return None + + @staticmethod + def get_actor_by_name(role_name: str): + for actor_id in CarlaDataProvider._carla_actor_pool: + if CarlaDataProvider._carla_actor_pool[actor_id].attributes["role_name"] == role_name: + return CarlaDataProvider._carla_actor_pool[actor_id] + print(f"Non-existing actor name {role_name}") + return None + + @staticmethod + def remove_actor_by_id(actor_id): + """Remove an actor from the pool using its ID.""" + if actor_id in CarlaDataProvider._carla_actor_pool: + CarlaDataProvider._carla_actor_pool[actor_id].destroy() + CarlaDataProvider._carla_actor_pool[actor_id] = None + CarlaDataProvider._carla_actor_pool.pop(actor_id) + else: + print("Trying to remove a non-existing actor id {}".format(actor_id)) + + @staticmethod + def remove_actors_in_surrounding(location, distance): + """Remove all actors from the pool that are closer than distance to the provided location.""" + for actor_id in CarlaDataProvider._carla_actor_pool.copy(): + if ( + CarlaDataProvider._carla_actor_pool[actor_id].get_location().distance(location) + < distance + ): + CarlaDataProvider._carla_actor_pool[actor_id].destroy() + CarlaDataProvider._carla_actor_pool.pop(actor_id) + + # Remove all keys with None values + CarlaDataProvider._carla_actor_pool = dict( + {k: v for k, v in CarlaDataProvider._carla_actor_pool.items() if v} + ) + + @staticmethod + def get_traffic_manager_port(): + """Get the port of the traffic manager.""" + return CarlaDataProvider._traffic_manager_port + + @staticmethod + def set_traffic_manager_port(tm_port): + """Set the port to use for the traffic manager.""" + CarlaDataProvider._traffic_manager_port = tm_port + + @staticmethod + def cleanup(): + """Cleanup and remove all entries from all dictionaries.""" + DestroyActor = carla.command.DestroyActor # pylint: disable=invalid-name + batch = [] + + for actor_id in CarlaDataProvider._carla_actor_pool.copy(): + actor = CarlaDataProvider._carla_actor_pool[actor_id] + if actor is not None and actor.is_alive: + batch.append(DestroyActor(actor)) + + if CarlaDataProvider._client: + try: + CarlaDataProvider._client.apply_batch_sync(batch) + except RuntimeError as e: + if "time-out" in str(e): + pass + else: + raise e + + CarlaDataProvider._actor_velocity_map.clear() + CarlaDataProvider._actor_location_map.clear() + CarlaDataProvider._actor_transform_map.clear() + CarlaDataProvider._traffic_light_map.clear() + CarlaDataProvider._map = None + CarlaDataProvider._world = None + CarlaDataProvider._sync_flag = False + CarlaDataProvider._ego_vehicle_route = None + CarlaDataProvider._all_actors = None + CarlaDataProvider._carla_actor_pool = {} + CarlaDataProvider._client = None + CarlaDataProvider._spawn_points = None + CarlaDataProvider._spawn_index = 0 + CarlaDataProvider._rng = random.RandomState(CarlaDataProvider._random_seed) + CarlaDataProvider._runtime_init_flag = False + + @property + def world(self): + return self._world + + +class GameTime(object): + """Provides access to the CARLA game time.""" + + _current_game_time = 0.0 # Elapsed game time after starting this Timer + _carla_time = 0.0 + _last_frame = 0 + _platform_timestamp = 0 + _init = False + + @staticmethod + def on_carla_tick(timestamp): + """Handle the callback receiving the CARLA time. Update time only when the frame is more recent than the last frame.""" + if GameTime._last_frame < timestamp.frame: + frames = timestamp.frame - GameTime._last_frame if GameTime._init else 1 + GameTime._current_game_time += timestamp.delta_seconds * frames + GameTime._last_frame = timestamp.frame + GameTime._platform_timestamp = datetime.datetime.now() + GameTime._init = True + GameTime._carla_time = timestamp.elapsed_seconds + + @staticmethod + def restart(): + """Reset game timer to 0.""" + GameTime._current_game_time = 0.0 + GameTime._carla_time = 0.0 + GameTime._last_frame = 0 + GameTime._init = False + + @staticmethod + def get_time(): + """Return elapsed game time.""" + return GameTime._current_game_time + + @staticmethod + def get_carla_time(): + """Return elapsed game time.""" + return GameTime._carla_time + + @staticmethod + def get_wallclocktime(): + """Return elapsed game time.""" + return GameTime._platform_timestamp + + @staticmethod + def get_frame(): + """Return elapsed game time.""" + return GameTime._last_frame diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py new file mode 100644 index 0000000000000..697a4405131b2 --- /dev/null +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -0,0 +1,99 @@ +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.sr/bin/env python + +import ctypes +import math +import struct +import sys + +from geometry_msgs.msg import Point +from geometry_msgs.msg import Quaternion +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from transforms3d.euler import euler2quat + + +def _get_struct_fmt(is_bigendian, fields, field_names=None): + _DATATYPES = {} + _DATATYPES[PointField.INT8] = ("b", 1) + _DATATYPES[PointField.UINT8] = ("B", 1) + _DATATYPES[PointField.INT16] = ("h", 2) + _DATATYPES[PointField.UINT16] = ("H", 2) + _DATATYPES[PointField.INT32] = ("i", 4) + _DATATYPES[PointField.UINT32] = ("I", 4) + _DATATYPES[PointField.FLOAT32] = ("f", 4) + _DATATYPES[PointField.FLOAT64] = ("d", 8) + + fmt = ">" if is_bigendian else "<" + + offset = 0 + for field in ( + f + for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names + ): + if offset < field.offset: + fmt += "x" * (field.offset - offset) + offset = field.offset + if field.datatype not in _DATATYPES: + print("Skipping unknown PointField datatype [{}]" % field.datatype, file=sys.stderr) + else: + datatype_fmt, datatype_length = _DATATYPES[field.datatype] + fmt += field.count * datatype_fmt + offset += field.count * datatype_length + + return fmt + + +def create_cloud(header, fields, points): + """Create a L{sensor_msgs.msg.PointCloud2} message with different datatype.""" + cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into + offset = 0 + for p in points: + pack_into(buff, offset, *p) + offset += point_step + + return PointCloud2( + header=header, + height=1, + width=len(points), + is_dense=False, + is_bigendian=False, + fields=fields, + point_step=cloud_struct.size, + row_step=cloud_struct.size * len(points), + data=buff.raw, + ) + + +def carla_location_to_ros_point(carla_location): + """Convert a carla location to a ROS point.""" + ros_point = Point() + ros_point.x = carla_location.x + ros_point.y = -carla_location.y + ros_point.z = carla_location.z + + return ros_point + + +def carla_rotation_to_ros_quaternion(carla_rotation): + """Convert a carla rotation to a ROS quaternion.""" + roll = math.radians(carla_rotation.roll) + pitch = -math.radians(carla_rotation.pitch) + yaw = -math.radians(carla_rotation.yaw) + quat = euler2quat(roll, pitch, yaw) + ros_quaternion = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) + return ros_quaternion diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py new file mode 100644 index 0000000000000..d5b1fdb6b4d9b --- /dev/null +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py @@ -0,0 +1,227 @@ +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.sr/bin/env python + +from __future__ import print_function + +import logging +from queue import Empty +from queue import Queue + +import carla +import numpy as np + +from .carla_data_provider import CarlaDataProvider + + +# Sensor Wrapper for Agent +class SensorReceivedNoData(Exception): + """Exceptions when no data received from the sensors.""" + + +class GenericMeasurement(object): + def __init__(self, data, frame): + self.data = data + self.frame = frame + + +class CallBack(object): + def __init__(self, tag, sensor, data_provider): + self._tag = tag + self._data_provider = data_provider + + self._data_provider.register_sensor(tag, sensor) + + def __call__(self, data): + if isinstance(data, carla.Image): + self._parse_image_cb(data, self._tag) + elif isinstance(data, carla.LidarMeasurement): + self._parse_lidar_cb(data, self._tag) + elif isinstance(data, carla.GnssMeasurement): + self._parse_gnss_cb(data, self._tag) + elif isinstance(data, carla.IMUMeasurement): + self._parse_imu_cb(data, self._tag) + elif isinstance(data, GenericMeasurement): + self._parse_pseudosensor(data, self._tag) + else: + logging.error("No callback method for this sensor.") + + # Parsing CARLA physical Sensors + def _parse_image_cb(self, image, tag): + self._data_provider.update_sensor(tag, image, image.frame) + + def _parse_lidar_cb(self, lidar_data, tag): + self._data_provider.update_sensor(tag, lidar_data, lidar_data.frame) + + def _parse_imu_cb(self, imu_data, tag): + self._data_provider.update_sensor(tag, imu_data, imu_data.frame) + + def _parse_gnss_cb(self, gnss_data, tag): + array = np.array( + [gnss_data.latitude, gnss_data.longitude, gnss_data.altitude], dtype=np.float64 + ) + self._data_provider.update_sensor(tag, array, gnss_data.frame) + + def _parse_pseudosensor(self, package, tag): + self._data_provider.update_sensor(tag, package.data, package.frame) + + +class SensorInterface(object): + def __init__(self): + self._sensors_objects = {} + self._new_data_buffers = Queue() + self._queue_timeout = 10 + self.tag = "" + + def register_sensor(self, tag, sensor): + self.tag = tag + if tag in self._sensors_objects: + raise ValueError(f"Duplicated sensor tag [{tag}]") + + self._sensors_objects[tag] = sensor + + def update_sensor(self, tag, data, timestamp): + if tag not in self._sensors_objects: + raise ValueError(f"Sensor with tag [{tag}] has not been created") + + self._new_data_buffers.put((tag, timestamp, data)) + + def get_data(self): + try: + data_dict = {} + while len(data_dict.keys()) < len(self._sensors_objects.keys()): + sensor_data = self._new_data_buffers.get(True, self._queue_timeout) + data_dict[sensor_data[0]] = (sensor_data[1], sensor_data[2]) + except Empty: + raise SensorReceivedNoData( + f"Sensor with tag [{self.tag}] took too long to send its data" + ) + + return data_dict + + +# Sensor Wrapper + + +class SensorWrapper(object): + _agent = None + _sensors_list = [] + + def __init__(self, agent): + self._agent = agent + + def __call__(self): + return self._agent() + + def setup_sensors(self, vehicle, debug_mode=False): + """Create and attach the sensor defined in objects.json.""" + bp_library = CarlaDataProvider.get_world().get_blueprint_library() + + for sensor_spec in self._agent.sensors["sensors"]: + bp = bp_library.find(str(sensor_spec["type"])) + + if sensor_spec["type"].startswith("sensor.camera"): + bp.set_attribute("image_size_x", str(sensor_spec["image_size_x"])) + bp.set_attribute("image_size_y", str(sensor_spec["image_size_y"])) + bp.set_attribute("fov", str(sensor_spec["fov"])) + sensor_location = carla.Location( + x=sensor_spec["spawn_point"]["x"], + y=sensor_spec["spawn_point"]["y"], + z=sensor_spec["spawn_point"]["z"], + ) + sensor_rotation = carla.Rotation( + pitch=sensor_spec["spawn_point"]["pitch"], + roll=sensor_spec["spawn_point"]["roll"], + yaw=sensor_spec["spawn_point"]["yaw"], + ) + + elif sensor_spec["type"].startswith("sensor.lidar"): + bp.set_attribute("range", str(sensor_spec["range"])) + bp.set_attribute("rotation_frequency", str(sensor_spec["rotation_frequency"])) + bp.set_attribute("channels", str(sensor_spec["channels"])) + bp.set_attribute("upper_fov", str(sensor_spec["upper_fov"])) + bp.set_attribute("lower_fov", str(sensor_spec["lower_fov"])) + bp.set_attribute("points_per_second", str(sensor_spec["points_per_second"])) + sensor_location = carla.Location( + x=sensor_spec["spawn_point"]["x"], + y=sensor_spec["spawn_point"]["y"], + z=sensor_spec["spawn_point"]["z"], + ) + sensor_rotation = carla.Rotation( + pitch=sensor_spec["spawn_point"]["pitch"], + roll=sensor_spec["spawn_point"]["roll"], + yaw=sensor_spec["spawn_point"]["yaw"], + ) + + elif sensor_spec["type"].startswith("sensor.other.gnss"): + bp.set_attribute("noise_alt_stddev", str(0.0)) + bp.set_attribute("noise_lat_stddev", str(0.0)) + bp.set_attribute("noise_lon_stddev", str(0.0)) + bp.set_attribute("noise_alt_bias", str(0.0)) + bp.set_attribute("noise_lat_bias", str(0.0)) + bp.set_attribute("noise_lon_bias", str(0.0)) + sensor_location = carla.Location( + x=sensor_spec["spawn_point"]["x"], + y=sensor_spec["spawn_point"]["y"], + z=sensor_spec["spawn_point"]["z"], + ) + sensor_rotation = carla.Rotation() + + elif sensor_spec["type"].startswith("sensor.other.imu"): + bp.set_attribute("noise_accel_stddev_x", str(0.0)) + bp.set_attribute("noise_accel_stddev_y", str(0.0)) + bp.set_attribute("noise_accel_stddev_z", str(0.0)) + bp.set_attribute("noise_gyro_stddev_x", str(0.0)) + bp.set_attribute("noise_gyro_stddev_y", str(0.0)) + bp.set_attribute("noise_gyro_stddev_z", str(0.0)) + sensor_location = carla.Location( + x=sensor_spec["spawn_point"]["x"], + y=sensor_spec["spawn_point"]["y"], + z=sensor_spec["spawn_point"]["z"], + ) + sensor_rotation = carla.Rotation( + pitch=sensor_spec["spawn_point"]["pitch"], + roll=sensor_spec["spawn_point"]["roll"], + yaw=sensor_spec["spawn_point"]["yaw"], + ) + + elif sensor_spec["type"].startswith("sensor.pseudo.*"): + sensor_location = carla.Location( + x=sensor_spec["spawn_point"]["x"], + y=sensor_spec["spawn_point"]["y"], + z=sensor_spec["spawn_point"]["z"], + ) + sensor_rotation = carla.Rotation( + pitch=sensor_spec["spawn_point"]["pitch"], + roll=sensor_spec["spawn_point"]["roll"], + yaw=sensor_spec["spawn_point"]["yaw"], + ) + + # create sensor + sensor_transform = carla.Transform(sensor_location, sensor_rotation) + sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle) + # setup callback + sensor.listen(CallBack(sensor_spec["id"], sensor, self._agent.sensor_interface)) + self._sensors_list.append(sensor) + + # Tick once to spawn the sensors + CarlaDataProvider.get_world().tick() + + def cleanup(self): + """Cleanup sensors.""" + for i, _ in enumerate(self._sensors_list): + if self._sensors_list[i] is not None: + self._sensors_list[i].stop() + self._sensors_list[i].destroy() + self._sensors_list[i] = None + self._sensors_list = [] From 633c5098d5a29027cd0db5653a32f3755a23d980 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 22 Apr 2024 16:08:21 +0900 Subject: [PATCH 14/50] small update --- simulator/carla_autoware/README.md | 6 ++--- .../modules/carla_data_provider.py | 22 +++++++++++++++++++ 2 files changed, 24 insertions(+), 4 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 4e1300e274e77..6ed3666de06bd 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -2,12 +2,9 @@ # ROS2/Autoware.universe bridge for CARLA simulator -### Thanks to for ROS2 Humble support for CARLA ROS bridge - +Thanks to for ROS2 Humble support for CARLA Communication. This ros package enables communication between Autoware and CARLA for autonomous driving simulation. -- Make sure to Install the python .whl using pip to use CARLA with ROS2 Humble from [here](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04). - # Environment | ubuntu | ros | carla | autoware | @@ -24,6 +21,7 @@ This ros package enables communication between Autoware and CARLA for autonomous - [Carla Sensor Kit](https://github.com/mraditya01/carla_sensor_kit_launch) - [Autoware Individual params (forked with CARLA Sensor Kit params)](https://github.com/mraditya01/autoware_individual_params) - [Autoware launch with CARLA option](https://github.com/mraditya01/autoware_launch) +- [Python wheel for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index 4e606e336a9f9..cb9896d97afd7 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -191,6 +191,13 @@ def set_client(client): def get_client(): """Get the CARLA client.""" return CarlaDataProvider._client + + @staticmethod + def is_sync_mode(): + """ + @return true if syncronuous mode is used + """ + return CarlaDataProvider._sync_flag @staticmethod def set_world(world): @@ -206,6 +213,21 @@ def set_world(world): def get_world(): """Return world.""" return CarlaDataProvider._world + + @staticmethod + def get_map(world=None): + """Get the current map""" + if CarlaDataProvider._map is None: + if world is None: + if CarlaDataProvider._world is None: + raise ValueError("class member \'world'\' not initialized yet") + else: + CarlaDataProvider._map = CarlaDataProvider._world.get_map() + else: + CarlaDataProvider._map = world.get_map() + + return CarlaDataProvider._map + @staticmethod def get_all_actors(): From 9604b64e353478376fd196ff42522cf1e642e438 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 22 Apr 2024 07:18:49 +0000 Subject: [PATCH 15/50] style(pre-commit): autofix --- .../src/carla_autoware/modules/carla_data_provider.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index cb9896d97afd7..4a1a597219aff 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -191,7 +191,7 @@ def set_client(client): def get_client(): """Get the CARLA client.""" return CarlaDataProvider._client - + @staticmethod def is_sync_mode(): """ @@ -213,14 +213,14 @@ def set_world(world): def get_world(): """Return world.""" return CarlaDataProvider._world - + @staticmethod def get_map(world=None): """Get the current map""" if CarlaDataProvider._map is None: if world is None: if CarlaDataProvider._world is None: - raise ValueError("class member \'world'\' not initialized yet") + raise ValueError("class member 'world'' not initialized yet") else: CarlaDataProvider._map = CarlaDataProvider._world.get_map() else: @@ -228,7 +228,6 @@ def get_map(world=None): return CarlaDataProvider._map - @staticmethod def get_all_actors(): """Return all the world actors.""" From 86be60b5ef20886c4bc5c2a557dfb27527e85a86 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 3 May 2024 10:11:57 +0900 Subject: [PATCH 16/50] added multiple lidar support and carla sensor kit is not needed anymore --- simulator/carla_autoware/README.md | 5 +- simulator/carla_autoware/config/objects.json | 38 +++++++-- .../launch/carla_autoware.launch.xml | 6 +- simulator/carla_autoware/setup.py | 1 + .../src/carla_autoware/carla_ros.py | 41 ++++++---- .../modules/carla_data_provider.py | 20 ++--- .../src/carla_autoware/modules/carla_utils.py | 77 +++++++------------ .../carla_autoware/modules/carla_wrapper.py | 12 ++- 8 files changed, 113 insertions(+), 87 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 6ed3666de06bd..01522f9d35404 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -18,8 +18,6 @@ This ros package enables communication between Autoware and CARLA for autonomous - [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) -- [Carla Sensor Kit](https://github.com/mraditya01/carla_sensor_kit_launch) -- [Autoware Individual params (forked with CARLA Sensor Kit params)](https://github.com/mraditya01/autoware_individual_params) - [Autoware launch with CARLA option](https://github.com/mraditya01/autoware_launch) - [Python wheel for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) @@ -46,7 +44,7 @@ cd CARLA 2. Run ros nodes ```bash -ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=carla_sensor_kit simulator_type:=carla +ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla ``` 3. Set initial pose (Init by GNSS) @@ -57,5 +55,4 @@ ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map # Tips - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. -- You will also need to edit the `carla_sensor_kit_description` if you change the sensor configuration. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index 4cc82a2743cf0..7f31dbf262714 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -17,18 +17,37 @@ }, { "type": "sensor.lidar.ray_cast", - "id": "lidar", + "id": "left", "spawn_point": { "x": 0.0, "y": 0.0, - "z": 2.6, + "z": 4.6, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, "range": 50, - "channels": 64, - "points_per_second": 480000, + "channels": 32, + "points_per_second": 100000, + "upper_fov": 3.0, + "lower_fov": -27.0, + "rotation_frequency": 20, + "noise_stddev": 0.0 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "top", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 2.6, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "range": 20, + "channels": 32, + "points_per_second": 200000, "upper_fov": 3.0, "lower_fov": -27.0, "rotation_frequency": 20, @@ -37,7 +56,14 @@ { "type": "sensor.other.gnss", "id": "gnss", - "spawn_point": { "x": 0.0, "y": 0.0, "z": 1.6 } + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 1.6, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + } }, { "type": "sensor.other.imu", @@ -52,4 +78,4 @@ } } ] -} +} \ No newline at end of file diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index 043ba0aadbd63..95875f34f83af 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -27,6 +27,10 @@ - + + + + + diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 223ca5b382dcb..91ea4091ffe68 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -28,4 +28,5 @@ "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], }, package_dir={"": "src"}, + ) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index c3037db4d25c1..7de11c693c6d4 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -60,7 +60,17 @@ def setup(self): self.id_to_camera_info_map = {} self.cv_bridge = CvBridge() self.first_ = True - self.sensor_frequencies = {"lidar": 11, "camera": 11, "imu": 50, "status": 50, "pose": 2} + self.pub_lidar = {} + + self.sensor_frequencies = { + "top": 11, + "left": 11, + "right": 11, + "camera": 11, + "imu": 50, + "status": 50, + "pose": 2, + } self.publish_prev_times = { sensor: datetime.datetime.now() for sensor in self.sensor_frequencies } @@ -132,9 +142,12 @@ def setup(self): CameraInfo, "/sensing/camera/traffic_light/camera_info", 1 ) elif sensor["type"] == "sensor.lidar.ray_cast": - self.pub_lidar = self.ros2_node.create_publisher( - PointCloud2, "/sensing/lidar/top/outlier_filtered/pointcloud", 10 - ) + if sensor["id"] in self.sensor_frequencies: + self.pub_lidar[sensor["id"]] = self.ros2_node.create_publisher( + PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud', 10 + ) + else: + self.logger.info("Please use Top, Right, or Left as the LIDAR ID") elif sensor["type"] == "sensor.other.imu": self.pub_imu = self.ros2_node.create_publisher( Imu, "/sensing/imu/tamagawa/imu_raw", 1 @@ -194,13 +207,13 @@ def get_msg_header(self, frame_id): header.stamp = Time(sec=seconds, nanosec=nanoseconds) return header - def lidar(self, carla_lidar_measurement): + def lidar(self, carla_lidar_measurement, id_): """Transform the a received lidar measurement into a ROS point cloud message.""" - if self.checkFrequency("lidar"): + if self.checkFrequency(id_): return - self.publish_prev_times["lidar"] = datetime.datetime.now() + self.publish_prev_times[id_] = datetime.datetime.now() - header = self.get_msg_header(frame_id="velodyne_top") + header = self.get_msg_header(frame_id="velodyne_top_changed") fields = [ PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), @@ -223,7 +236,7 @@ def lidar(self, carla_lidar_measurement): lidar_data[:, 1] *= -1 point_cloud_msg = create_cloud(header, fields, lidar_data) - self.pub_lidar.publish(point_cloud_msg) + self.pub_lidar[id].publish(point_cloud_msg) def pose(self): """Transform odometry data to Pose and publish Pose with Covariance message.""" @@ -316,7 +329,9 @@ def camera(self, carla_camera_data): buffer=carla_camera_data.raw_data, ) img_msg = self.cv_bridge.cv2_to_imgmsg(image_data_array, encoding="bgra8") - img_msg.header = self.get_msg_header(frame_id="traffic_light_left_camera/camera_link") + img_msg.header = self.get_msg_header( + frame_id="traffic_light_left_camera/camera_link_changed" + ) cam_info = self._camera_info cam_info.header = img_msg.header self.pub_camera_info.publish(cam_info) @@ -329,7 +344,7 @@ def imu(self, carla_imu_measurement): self.publish_prev_times["imu"] = datetime.datetime.now() imu_msg = Imu() - imu_msg.header = self.get_msg_header(frame_id="tamagawa/imu_link") + imu_msg.header = self.get_msg_header(frame_id="tamagawa/imu_link_changed") imu_msg.angular_velocity.x = -carla_imu_measurement.gyroscope.x imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y imu_msg.angular_velocity.z = -carla_imu_measurement.gyroscope.z @@ -409,7 +424,7 @@ def run_step(self, input_data, timestamp): elif sensor_type == "sensor.other.gnss": self.pose() elif sensor_type == "sensor.lidar.ray_cast": - self.lidar(data[1]) + self.lidar(data[1], key) elif sensor_type == "sensor.other.imu": self.imu(data[1]) else: @@ -417,4 +432,4 @@ def run_step(self, input_data, timestamp): # Publish ego vehicle status self.ego_status() - return self.current_control + return self.current_control \ No newline at end of file diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index 4a1a597219aff..ee9d786230667 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -192,13 +192,6 @@ def get_client(): """Get the CARLA client.""" return CarlaDataProvider._client - @staticmethod - def is_sync_mode(): - """ - @return true if syncronuous mode is used - """ - return CarlaDataProvider._sync_flag - @staticmethod def set_world(world): """Set the world and world settings.""" @@ -213,14 +206,14 @@ def set_world(world): def get_world(): """Return world.""" return CarlaDataProvider._world - + @staticmethod def get_map(world=None): - """Get the current map""" + """Get the current map.""" if CarlaDataProvider._map is None: if world is None: if CarlaDataProvider._world is None: - raise ValueError("class member 'world'' not initialized yet") + raise ValueError("class member \'world'\' not initialized yet") else: CarlaDataProvider._map = CarlaDataProvider._world.get_map() else: @@ -228,6 +221,7 @@ def get_map(world=None): return CarlaDataProvider._map + @staticmethod def get_all_actors(): """Return all the world actors.""" @@ -757,6 +751,12 @@ def remove_actor_by_id(actor_id): CarlaDataProvider._carla_actor_pool.pop(actor_id) else: print("Trying to remove a non-existing actor id {}".format(actor_id)) + + @staticmethod + def is_sync_mode(): + """Return true if syncronuous mode is used.""" + return CarlaDataProvider._sync_flag + @staticmethod def remove_actors_in_surrounding(location, distance): diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py index 697a4405131b2..dca52187828ad 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -1,53 +1,33 @@ -# Copyright 2024 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License.sr/bin/env python - import ctypes -import math import struct +import math import sys -from geometry_msgs.msg import Point -from geometry_msgs.msg import Quaternion -from sensor_msgs.msg import PointCloud2 -from sensor_msgs.msg import PointField +from geometry_msgs.msg import Quaternion, Point from transforms3d.euler import euler2quat - +from sensor_msgs.msg import PointCloud2, PointField def _get_struct_fmt(is_bigendian, fields, field_names=None): _DATATYPES = {} - _DATATYPES[PointField.INT8] = ("b", 1) - _DATATYPES[PointField.UINT8] = ("B", 1) - _DATATYPES[PointField.INT16] = ("h", 2) - _DATATYPES[PointField.UINT16] = ("H", 2) - _DATATYPES[PointField.INT32] = ("i", 4) - _DATATYPES[PointField.UINT32] = ("I", 4) - _DATATYPES[PointField.FLOAT32] = ("f", 4) - _DATATYPES[PointField.FLOAT64] = ("d", 8) + _DATATYPES[PointField.INT8] = ('b', 1) + _DATATYPES[PointField.UINT8] = ('B', 1) + _DATATYPES[PointField.INT16] = ('h', 2) + _DATATYPES[PointField.UINT16] = ('H', 2) + _DATATYPES[PointField.INT32] = ('i', 4) + _DATATYPES[PointField.UINT32] = ('I', 4) + _DATATYPES[PointField.FLOAT32] = ('f', 4) + _DATATYPES[PointField.FLOAT64] = ('d', 8) - fmt = ">" if is_bigendian else "<" + fmt = '>' if is_bigendian else '<' offset = 0 - for field in ( - f - for f in sorted(fields, key=lambda f: f.offset) - if field_names is None or f.name in field_names - ): + for field in (f for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names): if offset < field.offset: - fmt += "x" * (field.offset - offset) + fmt += 'x' * (field.offset - offset) offset = field.offset if field.datatype not in _DATATYPES: - print("Skipping unknown PointField datatype [{}]" % field.datatype, file=sys.stderr) + print('Skipping unknown PointField datatype [{}]' % field.datatype, file=sys.stderr) else: datatype_fmt, datatype_length = _DATATYPES[field.datatype] fmt += field.count * datatype_fmt @@ -55,28 +35,27 @@ def _get_struct_fmt(is_bigendian, fields, field_names=None): return fmt - def create_cloud(header, fields, points): - """Create a L{sensor_msgs.msg.PointCloud2} message with different datatype.""" + """Create a L{sensor_msgs.msg.PointCloud2} message with different datatype (Modified create_cloud function).""" cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into offset = 0 for p in points: pack_into(buff, offset, *p) offset += point_step - return PointCloud2( - header=header, - height=1, - width=len(points), - is_dense=False, - is_bigendian=False, - fields=fields, - point_step=cloud_struct.size, - row_step=cloud_struct.size * len(points), - data=buff.raw, - ) + return PointCloud2(header=header, + height=1, + width=len(points), + is_dense=False, + is_bigendian=False, + fields=fields, + point_step=cloud_struct.size, + row_step=cloud_struct.size * len(points), + data=buff.raw) def carla_location_to_ros_point(carla_location): diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py index d5b1fdb6b4d9b..14647083fd6eb 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py @@ -175,7 +175,11 @@ def setup_sensors(self, vehicle, debug_mode=False): y=sensor_spec["spawn_point"]["y"], z=sensor_spec["spawn_point"]["z"], ) - sensor_rotation = carla.Rotation() + sensor_rotation = carla.Rotation( + pitch=sensor_spec["spawn_point"]["pitch"], + roll=sensor_spec["spawn_point"]["roll"], + yaw=sensor_spec["spawn_point"]["yaw"], + ) elif sensor_spec["type"].startswith("sensor.other.imu"): bp.set_attribute("noise_accel_stddev_x", str(0.0)) @@ -202,9 +206,9 @@ def setup_sensors(self, vehicle, debug_mode=False): z=sensor_spec["spawn_point"]["z"], ) sensor_rotation = carla.Rotation( - pitch=sensor_spec["spawn_point"]["pitch"], - roll=sensor_spec["spawn_point"]["roll"], - yaw=sensor_spec["spawn_point"]["yaw"], + pitch=sensor_spec["spawn_point"]["pitch"]+0.001, + roll=sensor_spec["spawn_point"]["roll"]-0.015, + yaw=sensor_spec["spawn_point"]["yaw"]+0.0364, ) # create sensor From 881b51bdb8b7be2b607fea078245bba9802b38a9 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 3 May 2024 10:14:21 +0900 Subject: [PATCH 17/50] fixed minor changes --- .pre-commit-config.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 7223a734c02d9..9d029d982e454 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -16,6 +16,12 @@ repos: - id: mixed-line-ending - id: trailing-whitespace args: [--markdown-linebreak-ext=md] + + - repo: https://github.com/igorshubovych/markdownlint-cli + rev: v0.33.0 + hooks: + - id: markdownlint + args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier rev: v3.0.0-alpha.6 From 3a8fa7f70c9f073250e3ba52af2fe5fae762fa34 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 3 May 2024 01:14:33 +0000 Subject: [PATCH 18/50] style(pre-commit): autofix --- simulator/carla_autoware/config/objects.json | 2 +- .../launch/carla_autoware.launch.xml | 8 ++- simulator/carla_autoware/setup.py | 1 - .../src/carla_autoware/carla_ros.py | 2 +- .../modules/carla_data_provider.py | 8 +-- .../src/carla_autoware/modules/carla_utils.py | 59 +++++++++++-------- .../carla_autoware/modules/carla_wrapper.py | 6 +- 7 files changed, 48 insertions(+), 38 deletions(-) diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index 7f31dbf262714..84ba977174c11 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -78,4 +78,4 @@ } } ] -} \ No newline at end of file +} diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index 95875f34f83af..8d34cea825257 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -31,6 +31,10 @@ - - + diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 91ea4091ffe68..223ca5b382dcb 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -28,5 +28,4 @@ "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], }, package_dir={"": "src"}, - ) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 7de11c693c6d4..5e45ee215ddc9 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -432,4 +432,4 @@ def run_step(self, input_data, timestamp): # Publish ego vehicle status self.ego_status() - return self.current_control \ No newline at end of file + return self.current_control diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index ee9d786230667..85c1b5d3624da 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -206,14 +206,14 @@ def set_world(world): def get_world(): """Return world.""" return CarlaDataProvider._world - + @staticmethod def get_map(world=None): """Get the current map.""" if CarlaDataProvider._map is None: if world is None: if CarlaDataProvider._world is None: - raise ValueError("class member \'world'\' not initialized yet") + raise ValueError("class member 'world'' not initialized yet") else: CarlaDataProvider._map = CarlaDataProvider._world.get_map() else: @@ -221,7 +221,6 @@ def get_map(world=None): return CarlaDataProvider._map - @staticmethod def get_all_actors(): """Return all the world actors.""" @@ -751,13 +750,12 @@ def remove_actor_by_id(actor_id): CarlaDataProvider._carla_actor_pool.pop(actor_id) else: print("Trying to remove a non-existing actor id {}".format(actor_id)) - + @staticmethod def is_sync_mode(): """Return true if syncronuous mode is used.""" return CarlaDataProvider._sync_flag - @staticmethod def remove_actors_in_surrounding(location, distance): """Remove all actors from the pool that are closer than distance to the provided location.""" diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py index dca52187828ad..0de11e695d0b0 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -1,33 +1,39 @@ import ctypes -import struct import math +import struct import sys -from geometry_msgs.msg import Quaternion, Point +from geometry_msgs.msg import Point +from geometry_msgs.msg import Quaternion +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField from transforms3d.euler import euler2quat -from sensor_msgs.msg import PointCloud2, PointField + def _get_struct_fmt(is_bigendian, fields, field_names=None): _DATATYPES = {} - _DATATYPES[PointField.INT8] = ('b', 1) - _DATATYPES[PointField.UINT8] = ('B', 1) - _DATATYPES[PointField.INT16] = ('h', 2) - _DATATYPES[PointField.UINT16] = ('H', 2) - _DATATYPES[PointField.INT32] = ('i', 4) - _DATATYPES[PointField.UINT32] = ('I', 4) - _DATATYPES[PointField.FLOAT32] = ('f', 4) - _DATATYPES[PointField.FLOAT64] = ('d', 8) + _DATATYPES[PointField.INT8] = ("b", 1) + _DATATYPES[PointField.UINT8] = ("B", 1) + _DATATYPES[PointField.INT16] = ("h", 2) + _DATATYPES[PointField.UINT16] = ("H", 2) + _DATATYPES[PointField.INT32] = ("i", 4) + _DATATYPES[PointField.UINT32] = ("I", 4) + _DATATYPES[PointField.FLOAT32] = ("f", 4) + _DATATYPES[PointField.FLOAT64] = ("d", 8) - fmt = '>' if is_bigendian else '<' + fmt = ">" if is_bigendian else "<" offset = 0 - for field in (f for f in sorted(fields, key=lambda f: f.offset) - if field_names is None or f.name in field_names): + for field in ( + f + for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names + ): if offset < field.offset: - fmt += 'x' * (field.offset - offset) + fmt += "x" * (field.offset - offset) offset = field.offset if field.datatype not in _DATATYPES: - print('Skipping unknown PointField datatype [{}]' % field.datatype, file=sys.stderr) + print("Skipping unknown PointField datatype [{}]" % field.datatype, file=sys.stderr) else: datatype_fmt, datatype_length = _DATATYPES[field.datatype] fmt += field.count * datatype_fmt @@ -35,6 +41,7 @@ def _get_struct_fmt(is_bigendian, fields, field_names=None): return fmt + def create_cloud(header, fields, points): """Create a L{sensor_msgs.msg.PointCloud2} message with different datatype (Modified create_cloud function).""" cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) @@ -47,15 +54,17 @@ def create_cloud(header, fields, points): pack_into(buff, offset, *p) offset += point_step - return PointCloud2(header=header, - height=1, - width=len(points), - is_dense=False, - is_bigendian=False, - fields=fields, - point_step=cloud_struct.size, - row_step=cloud_struct.size * len(points), - data=buff.raw) + return PointCloud2( + header=header, + height=1, + width=len(points), + is_dense=False, + is_bigendian=False, + fields=fields, + point_step=cloud_struct.size, + row_step=cloud_struct.size * len(points), + data=buff.raw, + ) def carla_location_to_ros_point(carla_location): diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py index 14647083fd6eb..601bb4c8ac2cc 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py @@ -206,9 +206,9 @@ def setup_sensors(self, vehicle, debug_mode=False): z=sensor_spec["spawn_point"]["z"], ) sensor_rotation = carla.Rotation( - pitch=sensor_spec["spawn_point"]["pitch"]+0.001, - roll=sensor_spec["spawn_point"]["roll"]-0.015, - yaw=sensor_spec["spawn_point"]["yaw"]+0.0364, + pitch=sensor_spec["spawn_point"]["pitch"] + 0.001, + roll=sensor_spec["spawn_point"]["roll"] - 0.015, + yaw=sensor_spec["spawn_point"]["yaw"] + 0.0364, ) # create sensor From d89b90f897cda47ca34248ae88f949eeac519d9b Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 13 May 2024 09:18:21 +0900 Subject: [PATCH 19/50] fixed bug, readme, and performance --- .pre-commit-config.yaml | 2 +- simulator/carla_autoware/README.md | 14 +-- .../src/carla_autoware/carla_autoware.py | 2 +- .../src/carla_autoware/carla_ros.py | 107 +++++++++++------- .../src/carla_autoware/modules/carla_utils.py | 36 ++++++ 5 files changed, 113 insertions(+), 48 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 9d029d982e454..a5ca7b6cf37fa 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -16,7 +16,7 @@ repos: - id: mixed-line-ending - id: trailing-whitespace args: [--markdown-linebreak-ext=md] - + - repo: https://github.com/igorshubovych/markdownlint-cli rev: v0.33.0 hooks: diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 01522f9d35404..aaa6117a735ec 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -1,4 +1,4 @@ -# CARLA_Autoware +# CARLA Autoware # ROS2/Autoware.universe bridge for CARLA simulator @@ -7,9 +7,9 @@ This ros package enables communication between Autoware and CARLA for autonomous # Environment -| ubuntu | ros | carla | autoware | -| :----: | :----: | :----: | :-------------: | -| 22.04 | humble | 0.9.15 | universe/master | +| ubuntu | ros | carla | autoware | +| :----: | :----: | :----: | :------: | +| 22.04 | humble | 0.9.15 | 2024.04 | # Setup @@ -18,11 +18,10 @@ This ros package enables communication between Autoware and CARLA for autonomous - [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) -- [Autoware launch with CARLA option](https://github.com/mraditya01/autoware_launch) - [Python wheel for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) 1. Download maps (y-axis inverted version) to arbitaly location - 2. Change names. (point_cloud/Town01.pcd -> Town01/pointcloud_map.pcd, vector_maps/lanelet2/Town01.osm -> Town01/lanelet2_map.osm) + 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. ## build @@ -44,7 +43,7 @@ cd CARLA 2. Run ros nodes ```bash -ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/carla_town_01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla +ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla ``` 3. Set initial pose (Init by GNSS) @@ -56,3 +55,4 @@ ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. +- Naming the map folder according to the name of the CARLA map is important! (example: `Town01`, `Town10HD`, `Town02`). diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 36d2fea5446e4..6eb08c0e95043 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -66,7 +66,7 @@ def __init__(self): self.timeout = self.param_["timeout"] self.sync_mode = self.param_["sync_mode"] self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] - self.map_name = self.param_["map_name"] + self.map_name = self.param_["map_name"].split("/")[4] self.agent_role_name = self.param_["ego_vehicle_role_name"] self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 5e45ee215ddc9..4b7aa3ec841c4 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -45,6 +45,8 @@ from .modules.carla_utils import carla_location_to_ros_point from .modules.carla_utils import carla_rotation_to_ros_quaternion from .modules.carla_utils import create_cloud +from .modules.carla_utils import ros_pose_to_carla_transform +from .modules.carla_utils import steer_to_angle_map from .modules.carla_wrapper import SensorInterface @@ -71,6 +73,7 @@ def setup(self): "status": 50, "pose": 2, } + self.max_steering_angle = 45 self.publish_prev_times = { sensor: datetime.datetime.now() for sensor in self.sensor_frequencies } @@ -109,6 +112,11 @@ def setup(self): self.sub_control = self.ros2_node.create_subscription( AckermannControlCommand, "/control/command/control_cmd", self.control_callback, 1 ) + + self.sub_vehicle_initialpose = self.ros2_node.create_subscription( + PoseWithCovarianceStamped, "initialpose", self.initialpose_callback, 1 + ) + self.current_control = carla.VehicleControl() # Direct data publishing from CARLA for Autoware @@ -136,7 +144,7 @@ def setup(self): self.id_to_sensor_type_map[sensor["id"]] = sensor["type"] if sensor["type"] == "sensor.camera.rgb": self.pub_camera = self.ros2_node.create_publisher( - Image, "/sensing/camera/traffic_light/image_raw", 1 + Image, "/perception/traffic_light_recognition/traffic_light/debug/rois", 1 ) self.pub_camera_info = self.ros2_node.create_publisher( CameraInfo, "/sensing/camera/traffic_light/camera_info", 1 @@ -169,27 +177,6 @@ def __call__(self): def get_param(self): return self.param_values - def control_callback(self, in_cmd): - """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" - out_cmd = carla.VehicleControl() - self.target_vel = abs(in_cmd.longitudinal.speed) - self.vel_diff = self.target_vel - self.current_vel - - if self.vel_diff > 0: - out_cmd.throttle = 0.75 - out_cmd.brake = 0.0 - elif self.vel_diff <= 0.0: - out_cmd.throttle = 0.0 - if self.target_vel <= 0.0: - out_cmd.brake = 0.75 - elif self.vel_diff > -1: - out_cmd.brake = 0.0 - else: - out_cmd.brake = 0.01 - - out_cmd.steer = -in_cmd.lateral.steering_tire_angle - self.current_control = out_cmd - def checkFrequency(self, sensor): time_delta = ( datetime.datetime.now() - self.publish_prev_times[sensor] @@ -236,7 +223,27 @@ def lidar(self, carla_lidar_measurement, id_): lidar_data[:, 1] *= -1 point_cloud_msg = create_cloud(header, fields, lidar_data) - self.pub_lidar[id].publish(point_cloud_msg) + self.pub_lidar[id_].publish(point_cloud_msg) + + def get_ego_vehicle(self): + for car in CarlaDataProvider.get_world().get_actors().filter("vehicle.*"): + if car.attributes["role_name"] == self.agent_role_name: + return car + return None + + def initialpose_callback(self, data): + """Transform RVIZ initial pose to CARLA.""" + self.ego_vehicle = CarlaDataProvider.get_actor_by_name( + self.param_values["ego_vehicle_role_name"] + ) + + pose = data.pose.pose + pose.position.z += 2.0 + carla_pose_transform = ros_pose_to_carla_transform(pose) + if self.ego_vehicle is not None: + self.ego_vehicle.set_transform(carla_pose_transform) + else: + print("Can't find Ego Vehicle") def pose(self): """Transform odometry data to Pose and publish Pose with Covariance message.""" @@ -245,15 +252,17 @@ def pose(self): self.publish_prev_times["pose"] = datetime.datetime.now() header = self.get_msg_header(frame_id="map") - ego_ = CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) - out_pose_with_cov = PoseWithCovarianceStamped() pose_carla = Pose() pose_carla.position = carla_location_to_ros_point( - CarlaDataProvider.get_transform(ego_).location + CarlaDataProvider.get_transform( + CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) + ).location ) pose_carla.orientation = carla_rotation_to_ros_quaternion( - CarlaDataProvider.get_transform(ego_).rotation + CarlaDataProvider.get_transform( + CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) + ).rotation ) out_pose_with_cov.header = header out_pose_with_cov.pose.pose = pose_carla @@ -365,22 +374,40 @@ def imu(self, carla_imu_measurement): self.pub_imu.publish(imu_msg) + def control_callback(self, in_cmd): + """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" + out_cmd = carla.VehicleControl() + self.target_vel = in_cmd.longitudinal.speed + self.vel_diff = self.target_vel - self.current_vel + + if self.vel_diff > 0: + out_cmd.throttle = 0.75 + out_cmd.brake = 0.0 + elif self.vel_diff <= 0.0: + out_cmd.throttle = 0.0 + if self.target_vel <= 0.0: + out_cmd.brake = 0.75 + elif self.vel_diff > -1: + out_cmd.brake = 0.0 + else: + out_cmd.brake = 0.01 + + out_cmd.steer = -in_cmd.lateral.steering_tire_angle + self.current_control = out_cmd + def ego_status(self): """Publish ego vehicle status.""" if self.checkFrequency("status"): return self.publish_prev_times["status"] = datetime.datetime.now() - - in_status = CarlaDataProvider.get_actor_by_name( - self.param_values["ego_vehicle_role_name"] - ).get_control() - velocity = CarlaDataProvider.get_actor_by_name( + ego_vehicle = CarlaDataProvider.get_actor_by_name( self.param_values["ego_vehicle_role_name"] - ).get_velocity() - vel_np = numpy.array([velocity.x, velocity.y, velocity.z]) - orientation = numpy.array([1, 1, 0]) - in_vel_state = numpy.abs(numpy.dot(vel_np, orientation)) - self.current_vel = in_vel_state + ) + + in_status = ego_vehicle.get_control() + self.current_vel = CarlaDataProvider.get_velocity( + CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) + ) out_vel_state = VelocityReport() out_steering_state = SteeringReport() @@ -389,12 +416,14 @@ def ego_status(self): out_traffic = TrafficSignalArray() out_vel_state.header = self.get_msg_header(frame_id="base_link") - out_vel_state.longitudinal_velocity = in_vel_state + out_vel_state.longitudinal_velocity = self.current_vel out_vel_state.lateral_velocity = 0.0 out_vel_state.heading_rate = 0.0 out_steering_state.stamp = out_vel_state.header.stamp - out_steering_state.steering_tire_angle = -in_status.steer + out_steering_state.steering_tire_angle = steer_to_angle_map(self.max_steering_angle)( + in_status.steer + ) out_gear_state.stamp = out_vel_state.header.stamp out_gear_state.report = GearReport.DRIVE diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py index 0de11e695d0b0..9def0c5d87dd1 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -3,11 +3,14 @@ import struct import sys +import carla from geometry_msgs.msg import Point from geometry_msgs.msg import Quaternion +import numpy as np from sensor_msgs.msg import PointCloud2 from sensor_msgs.msg import PointField from transforms3d.euler import euler2quat +from transforms3d.euler import quat2euler def _get_struct_fmt(is_bigendian, fields, field_names=None): @@ -84,4 +87,37 @@ def carla_rotation_to_ros_quaternion(carla_rotation): yaw = -math.radians(carla_rotation.yaw) quat = euler2quat(roll, pitch, yaw) ros_quaternion = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) + return ros_quaternion + + +def ros_quaternion_to_carla_rotation(ros_quaternion): + """Convert ROS quaternion to carla rotation.""" + roll, pitch, yaw = quat2euler( + [ros_quaternion.w, ros_quaternion.x, ros_quaternion.y, ros_quaternion.z] + ) + + return carla.Rotation( + roll=math.degrees(roll), pitch=-math.degrees(pitch), yaw=-math.degrees(yaw) + ) + + +def ros_pose_to_carla_transform(ros_pose): + """Convert ROS pose to carla transform.""" + return carla.Transform( + carla.Location(ros_pose.position.x, -ros_pose.position.y, ros_pose.position.z), + ros_quaternion_to_carla_rotation(ros_pose.orientation), + ) + + +def steer_to_angle_map(max_steering_angle): + """Compute the mapping from steering values to corresponding angles.""" + left_steer = -1 + right_steer = 1 + left_angle = np.radians(-max_steering_angle) + right_angle = -left_angle + steer_values = [left_steer, right_steer] + angle_values = [left_angle, right_angle] + coefficients = np.polyfit(steer_values, angle_values, 1) + mapping_function = np.poly1d(coefficients) + return mapping_function From 571ff336f2b3ec449832cb8ff9c607654b09b113 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Wed, 15 May 2024 10:38:04 +0900 Subject: [PATCH 20/50] fixed issue with map load --- simulator/carla_autoware/README.md | 10 +++++----- .../carla_autoware/launch/carla_autoware.launch.xml | 11 +++-------- .../src/carla_autoware/carla_autoware.py | 2 +- .../carla_autoware/src/carla_autoware/carla_ros.py | 2 +- 4 files changed, 10 insertions(+), 15 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index aaa6117a735ec..d7b1fa9972d1a 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -14,11 +14,11 @@ This ros package enables communication between Autoware and CARLA for autonomous # Setup ## install - -- [Autoware.Universe](https://autowarefoundation.github.io/autoware-documentation/galactic/installation/autoware/source-installation/) - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) -- [Python wheel for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) +- [Python Package for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) + - Install the wheel using pip. + - OR add the egg file to the `PYTHONPATH`. 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) @@ -43,7 +43,7 @@ cd CARLA 2. Run ros nodes ```bash -ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla +ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla ``` 3. Set initial pose (Init by GNSS) @@ -53,6 +53,6 @@ ros2 launch carla_autoware e2e_simulator.launch.xml map_path:=$HOME/autoware_map # Tips -- If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. +- If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. Make sure the sensor configuration is the same as the `sensor_kit` description used in Autoware. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. - Naming the map folder according to the name of the CARLA map is important! (example: `Town01`, `Town10HD`, `Town02`). diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index 8d34cea825257..5ce2a89303bde 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -5,7 +5,7 @@ - + @@ -20,7 +20,7 @@ - + @@ -31,10 +31,5 @@ - + diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 6eb08c0e95043..36d2fea5446e4 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -66,7 +66,7 @@ def __init__(self): self.timeout = self.param_["timeout"] self.sync_mode = self.param_["sync_mode"] self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] - self.map_name = self.param_["map_name"].split("/")[4] + self.map_name = self.param_["map_name"] self.agent_role_name = self.param_["ego_vehicle_role_name"] self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 4b7aa3ec841c4..5d274561d550d 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -88,7 +88,7 @@ def setup(self): "sync_mode": rclpy.Parameter.Type.BOOL, "timeout": rclpy.Parameter.Type.INTEGER, "fixed_delta_seconds": rclpy.Parameter.Type.DOUBLE, - "map_name": rclpy.Parameter.Type.STRING, + "carla_map_name": rclpy.Parameter.Type.STRING, "ego_vehicle_role_name": rclpy.Parameter.Type.STRING, "spawn_point": rclpy.Parameter.Type.STRING, "vehicle_type": rclpy.Parameter.Type.STRING, From f4611169968d05bf9ab9b364bd40df7466f72296 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 15 May 2024 01:42:13 +0000 Subject: [PATCH 21/50] style(pre-commit): autofix --- simulator/carla_autoware/README.md | 2 ++ simulator/carla_autoware/launch/carla_autoware.launch.xml | 7 ++++++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index d7b1fa9972d1a..12b27144f1bfb 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -14,9 +14,11 @@ This ros package enables communication between Autoware and CARLA for autonomous # Setup ## install + - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) - [Python Package for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) + - Install the wheel using pip. - OR add the egg file to the `PYTHONPATH`. diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index 5ce2a89303bde..d432292622a4b 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -31,5 +31,10 @@ - + From ced85044fb930cb93cbafa3b2e2683b0bbf44a80 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Wed, 15 May 2024 11:23:50 +0900 Subject: [PATCH 22/50] fixed readme --- simulator/carla_autoware/README.md | 7 +++---- .../carla_autoware/src/carla_autoware/carla_autoware.py | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 12b27144f1bfb..76309648a0df6 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -22,9 +22,9 @@ This ros package enables communication between Autoware and CARLA for autonomous - Install the wheel using pip. - OR add the egg file to the `PYTHONPATH`. - 1. Download maps (y-axis inverted version) to arbitaly location - 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) - 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. +1. Download maps (y-axis inverted version) to arbitaly location +2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) +3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. ## build @@ -57,4 +57,3 @@ ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_ma - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. Make sure the sensor configuration is the same as the `sensor_kit` description used in Autoware. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. -- Naming the map folder according to the name of the CARLA map is important! (example: `Town01`, `Town10HD`, `Town02`). diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 36d2fea5446e4..0415020e18670 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -66,7 +66,7 @@ def __init__(self): self.timeout = self.param_["timeout"] self.sync_mode = self.param_["sync_mode"] self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] - self.map_name = self.param_["map_name"] + self.map_name = self.param_["carla_map_name"] self.agent_role_name = self.param_["ego_vehicle_role_name"] self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] From b083cd10380927137e4b7fc1c1922453ae1e31d6 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Wed, 15 May 2024 12:08:54 +0900 Subject: [PATCH 23/50] added additional readme and fixed objects.json --- simulator/carla_autoware/README.md | 14 +++++++++++--- simulator/carla_autoware/config/objects.json | 19 ------------------- .../launch/carla_autoware.launch.xml | 4 ++-- .../src/carla_autoware/carla_autoware.py | 2 +- .../src/carla_autoware/carla_ros.py | 4 ++-- 5 files changed, 16 insertions(+), 27 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 76309648a0df6..4d445c5f81a81 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -5,7 +5,7 @@ Thanks to for ROS2 Humble support for CARLA Communication. This ros package enables communication between Autoware and CARLA for autonomous driving simulation. -# Environment +# Supported Environment | ubuntu | ros | carla | autoware | | :----: | :----: | :----: | :------: | @@ -26,7 +26,7 @@ This ros package enables communication between Autoware and CARLA for autonomous 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. -## build +## Build ```bash cd colcon_ws @@ -45,7 +45,7 @@ cd CARLA 2. Run ros nodes ```bash -ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla +ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla carla_map:=Town01 ``` 3. Set initial pose (Init by GNSS) @@ -57,3 +57,11 @@ ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_ma - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. Make sure the sensor configuration is the same as the `sensor_kit` description used in Autoware. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. +- Sensor frequency can be changed on `carla_ros.py` Line 67. +- Changing the `fixed_delta_seconds` can increase the simulation tick (clock), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). + +# Known Issues and Future Works + +- Testing on procedural map (Adv Digital Twin). +- Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. +- Traffic light recognition. \ No newline at end of file diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index 84ba977174c11..a240b8758321d 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -15,25 +15,6 @@ "image_size_y": 360, "fov": 90.0 }, - { - "type": "sensor.lidar.ray_cast", - "id": "left", - "spawn_point": { - "x": 0.0, - "y": 0.0, - "z": 4.6, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0 - }, - "range": 50, - "channels": 32, - "points_per_second": 100000, - "upper_fov": 3.0, - "lower_fov": -27.0, - "rotation_frequency": 20, - "noise_stddev": 0.0 - }, { "type": "sensor.lidar.ray_cast", "id": "top", diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index d432292622a4b..b949d71149a26 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -5,7 +5,7 @@ - + @@ -20,7 +20,7 @@ - + diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 0415020e18670..cabcf5fc4fdb0 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -66,7 +66,7 @@ def __init__(self): self.timeout = self.param_["timeout"] self.sync_mode = self.param_["sync_mode"] self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] - self.map_name = self.param_["carla_map_name"] + self.map_name = self.param_["carla_map"] self.agent_role_name = self.param_["ego_vehicle_role_name"] self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 5d274561d550d..a9b6caba471ed 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -88,7 +88,7 @@ def setup(self): "sync_mode": rclpy.Parameter.Type.BOOL, "timeout": rclpy.Parameter.Type.INTEGER, "fixed_delta_seconds": rclpy.Parameter.Type.DOUBLE, - "carla_map_name": rclpy.Parameter.Type.STRING, + "carla_map": rclpy.Parameter.Type.STRING, "ego_vehicle_role_name": rclpy.Parameter.Type.STRING, "spawn_point": rclpy.Parameter.Type.STRING, "vehicle_type": rclpy.Parameter.Type.STRING, @@ -144,7 +144,7 @@ def setup(self): self.id_to_sensor_type_map[sensor["id"]] = sensor["type"] if sensor["type"] == "sensor.camera.rgb": self.pub_camera = self.ros2_node.create_publisher( - Image, "/perception/traffic_light_recognition/traffic_light/debug/rois", 1 + Image, "/sensing/camera/traffic_light/image_raw", 1 ) self.pub_camera_info = self.ros2_node.create_publisher( CameraInfo, "/sensing/camera/traffic_light/camera_info", 1 From bc69f99c6bb9625d65d245b058058aa3cd552018 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 15 May 2024 03:11:54 +0000 Subject: [PATCH 24/50] style(pre-commit): autofix --- simulator/carla_autoware/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 4d445c5f81a81..f76bceb8c29a2 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -64,4 +64,4 @@ ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_ma - Testing on procedural map (Adv Digital Twin). - Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. -- Traffic light recognition. \ No newline at end of file +- Traffic light recognition. From 716ca1b62aa357d2e4b7d1a212bd8e578abe63df Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Wed, 15 May 2024 14:20:55 +0900 Subject: [PATCH 25/50] fixed readme --- simulator/carla_autoware/README.md | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index f76bceb8c29a2..2d413761cfc1f 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -1,19 +1,19 @@ # CARLA Autoware -# ROS2/Autoware.universe bridge for CARLA simulator +## ROS2/Autoware.universe bridge for CARLA simulator Thanks to for ROS2 Humble support for CARLA Communication. This ros package enables communication between Autoware and CARLA for autonomous driving simulation. -# Supported Environment +## Supported Environment | ubuntu | ros | carla | autoware | | :----: | :----: | :----: | :------: | | 22.04 | humble | 0.9.15 | 2024.04 | -# Setup +## Setup -## install +### Install - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) @@ -26,41 +26,41 @@ This ros package enables communication between Autoware and CARLA for autonomous 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) 3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. -## Build +### Build ```bash cd colcon_ws colcon build --symlink-install ``` -# Run +### Run 1. Run carla, change map, spawn object if you need -```bash -cd CARLA -./CarlaUE4.sh -prefernvidia -quality-level=Low -RenderOffScreen -``` + ```bash + cd CARLA + ./CarlaUE4.sh -prefernvidia -quality-level=Low -RenderOffScreen + ``` 2. Run ros nodes -```bash -ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla carla_map:=Town01 -``` + ```bash + ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla carla_map:=Town01 + ``` 3. Set initial pose (Init by GNSS) 4. Set goal position 5. Wait for planning 6. Engage -# Tips +### Tips - If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. Make sure the sensor configuration is the same as the `sensor_kit` description used in Autoware. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. - Sensor frequency can be changed on `carla_ros.py` Line 67. - Changing the `fixed_delta_seconds` can increase the simulation tick (clock), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). -# Known Issues and Future Works +### Known Issues and Future Works - Testing on procedural map (Adv Digital Twin). - Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. From 517aa4018e89105fded145b3d99253ae261d01bc Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 17 May 2024 18:24:11 +0900 Subject: [PATCH 26/50] Add traffic manager option and Improve README explanation --- simulator/carla_autoware/README.md | 89 +++++++++++++++++-- .../launch/carla_autoware.launch.xml | 7 +- .../src/carla_autoware/carla_autoware.py | 47 +++++++++- .../src/carla_autoware/carla_ros.py | 1 + 4 files changed, 129 insertions(+), 15 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 2d413761cfc1f..bcb32ead0f1ac 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -24,13 +24,12 @@ This ros package enables communication between Autoware and CARLA for autonomous 1. Download maps (y-axis inverted version) to arbitaly location 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) -3. Create `map_projector_info.yaml` and add `projector_type: local` on the first line. +3. Create `map_projector_info.yaml` on the folder and add `projector_type: local` on the first line. ### Build ```bash -cd colcon_ws -colcon build --symlink-install +colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ``` ### Run @@ -53,15 +52,89 @@ colcon build --symlink-install 5. Wait for planning 6. Engage -### Tips +## Inner-workings / Algorithms + +The main class responsible for setting up the CARLA world and the ego vehicle is InitializeInterface. The configuration parameters are fetched using the carla_interface. + +### Configureable Parameters for World Loading + +All the key parameters can be configured in `carla_autoware.launch.xml`. + +| Name | Type | Default Value | Description | +| ------------------------- | ------ | ----------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `host` | string | "localhost" | Hostname for the CARLA server | +| `port` | int | "2000" | Port number for the CARLA server | +| `timeout` | int | 20 | Timeout for the CARLA client | +| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | +| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | +| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | +| `carla_map` | string | "Town01" | Name of the map to load in CARLA | +| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | +| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | +| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | +| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | + +### Configurable Parameters for Sensors + +Below parameters can be configured in `carla_ros.py`. + +| Name | Type | Default Value | Description | +| ------------------------- | ---- | -------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `self.sensor_frequencies` | dict | {"top": 11, "left": 11, "right": 11, "camera": 11, "imu": 50, "status": 50, "pose": 2} | (line 67) Calculates the time interval since the last publication and checks if this interval meets the minimum required to not exceed the desired frequency. It will only affect ROS publishing frequency not CARLA sensor tick. | +| `self.max_steering_angle` | int | 45 | (Line 74) Maximum steering angle of a vehicle in degrees, used as parameter to compute the mapping from normalized steering input values. | + +- CARLA sensor parameters can be configured in `config/objects.json`. + - For more details regarding the parameters that can be modified in CARLA are explained in [Carla Ref Sensor](https://carla.readthedocs.io/en/latest/ref_sensors/). + +### World Loading + +The `carla_ros.py` sets up the CARLA world: + +1. **Client Connection**: + + ```python + client = carla.Client(self.local_host, self.port) + client.set_timeout(self.timeout) + ``` + +2. **Load the Map**: + + Map loaded in CALRA world with map according to `carla_map` parameter. + + ```python + client.load_world(self.map_name) + self.world = client.get_world() + ``` + +3. **Spawn Ego Vehicle**: + + Vehicle are spawn according to `vehicle_type`, `spawn_point`, and `agent_role_name` parameter. + + ```python + spawn_point = carla.Transform() + point_items = self.spawn_point.split(",") + if len(point_items) == 6: + spawn_point.location.x = float(point_items[0]) + spawn_point.location.y = float(point_items[1]) + spawn_point.location.z = float(point_items[2]) + 2 + spawn_point.rotation.roll = float(point_items[3]) + spawn_point.rotation.pitch = float(point_items[4]) + spawn_point.rotation.yaw = float(point_items[5]) + CarlaDataProvider.request_new_actor(self.vehicle_type, spawn_point, self.agent_role_name) + ``` + +## Tips -- If you want to edit the sensors configuration used in CARLA, edit `objects.json` located in `carla_autoware/config`. Make sure the sensor configuration is the same as the `sensor_kit` description used in Autoware. - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. -- Sensor frequency can be changed on `carla_ros.py` Line 67. -- Changing the `fixed_delta_seconds` can increase the simulation tick (clock), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). +- Changing the `fixed_delta_seconds` can increase the simulation tick (default 0.05 s), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). -### Known Issues and Future Works +## Known Issues and Future Works - Testing on procedural map (Adv Digital Twin). + - Currently unable to test it due to failing in the creation of the Adv digital twin map. - Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. + - Sensor currently not automatically configurated to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. - Traffic light recognition. + - Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition. +- Ego Vehicle Control. + - Currently during sharp turning the ego-vehicle have large lateral error. diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index b949d71149a26..588fd3eed515e 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -4,14 +4,12 @@ - + - - - + @@ -25,6 +23,7 @@ + diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index cabcf5fc4fdb0..961b25103ed69 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License.sr/bin/env python +import random import signal import time @@ -66,15 +67,16 @@ def __init__(self): self.timeout = self.param_["timeout"] self.sync_mode = self.param_["sync_mode"] self.fixed_delta_seconds = self.param_["fixed_delta_seconds"] - self.map_name = self.param_["carla_map"] + self.carla_map = self.param_["carla_map"] self.agent_role_name = self.param_["ego_vehicle_role_name"] self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] + self.use_traffic_manager = self.param_["use_traffic_manager"] def load_world(self): client = carla.Client(self.local_host, self.port) client.set_timeout(self.timeout) - client.load_world(self.map_name) + client.load_world(self.carla_map) self.world = client.get_world() if self.world is not None: settings = self.world.get_settings() @@ -90,7 +92,9 @@ def load_world(self): if len(point_items) == 6: spawn_point.location.x = float(point_items[0]) spawn_point.location.y = float(point_items[1]) - spawn_point.location.z = float(point_items[2]) + 2 + spawn_point.location.z = ( + float(point_items[2]) + 2 + ) # +2 is used so the car did not stuck on the road when spawned. spawn_point.rotation.roll = float(point_items[3]) spawn_point.rotation.pitch = float(point_items[4]) spawn_point.rotation.yaw = float(point_items[5]) @@ -103,6 +107,43 @@ def load_world(self): self.sensor_wrapper = SensorWrapper(self.interface) self.ego_vehicle = CarlaDataProvider.get_actor_by_name(self.agent_role_name) self.sensor_wrapper.setup_sensors(self.ego_vehicle, False) + ########################################################################################################################################################## + # TRAFFIC MANAGER + ########################################################################################################################################################## + if self.use_traffic_manager: + traffic_manager = client.get_trafficmanager() + traffic_manager.set_synchronous_mode(True) + traffic_manager.set_random_device_seed(0) + random.seed(0) + spawn_points_tm = self.world.get_map().get_spawn_points() + for i, spawn_point in enumerate(spawn_points_tm): + self.world.debug.draw_string(spawn_point.location, str(i), life_time=10) + models = [ + "dodge", + "audi", + "model3", + "mini", + "mustang", + "lincoln", + "prius", + "nissan", + "crown", + "impala", + ] + blueprints = [] + for vehicle in self.world.get_blueprint_library().filter("*vehicle*"): + if any(model in vehicle.id for model in models): + blueprints.append(vehicle) + max_vehicles = 30 + max_vehicles = min([max_vehicles, len(spawn_points_tm)]) + vehicles = [] + for i, spawn_point in enumerate(random.sample(spawn_points_tm, max_vehicles)): + temp = self.world.try_spawn_actor(random.choice(blueprints), spawn_point) + if temp is not None: + vehicles.append(temp) + + for vehicle in vehicles: + vehicle.set_autopilot(True) else: print("Carla Interface Couldn't find the world, Carla is not Running") diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index a9b6caba471ed..6514eb0e9003f 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -93,6 +93,7 @@ def setup(self): "spawn_point": rclpy.Parameter.Type.STRING, "vehicle_type": rclpy.Parameter.Type.STRING, "objects_definition_file": rclpy.Parameter.Type.STRING, + "use_traffic_manager": rclpy.Parameter.Type.BOOL, } self.param_values = {} for param_name, param_type in self.parameters.items(): From ea5bb33df393d50d5bd8d580032388cf7a1ad3c3 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 20 May 2024 11:18:45 +0900 Subject: [PATCH 27/50] Removed redundant files and dependencies --- simulator/carla_autoware/CMakeLists.txt | 5 +- simulator/carla_autoware/LICENSE | 201 ------------------ simulator/carla_autoware/package.xml | 6 +- .../carla_autoware/resource/carla_autoware | 0 simulator/carla_autoware/setup.py | 5 +- .../modules/carla_data_provider.py | 7 - 6 files changed, 5 insertions(+), 219 deletions(-) delete mode 100644 simulator/carla_autoware/LICENSE delete mode 100644 simulator/carla_autoware/resource/carla_autoware diff --git a/simulator/carla_autoware/CMakeLists.txt b/simulator/carla_autoware/CMakeLists.txt index 1062fd0247b07..7c02f26024b69 100644 --- a/simulator/carla_autoware/CMakeLists.txt +++ b/simulator/carla_autoware/CMakeLists.txt @@ -5,15 +5,14 @@ find_package(autoware_cmake REQUIRED) autoware_package() find_package( - catkin REQUIRED COMPONENTS rospy std_msgs - carla_msgs) + catkin REQUIRED COMPONENTS std_msgs) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -ament_export_dependencies(rclpy rospy) +ament_export_dependencies(rclpy) find_package(ros_environment REQUIRED) set(ROS_VERSION $ENV{ROS_VERSION}) diff --git a/simulator/carla_autoware/LICENSE b/simulator/carla_autoware/LICENSE deleted file mode 100644 index 261eeb9e9f8b2..0000000000000 --- a/simulator/carla_autoware/LICENSE +++ /dev/null @@ -1,201 +0,0 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. diff --git a/simulator/carla_autoware/package.xml b/simulator/carla_autoware/package.xml index fde3c0b16d9cc..abd665ba7b844 100644 --- a/simulator/carla_autoware/package.xml +++ b/simulator/carla_autoware/package.xml @@ -3,18 +3,14 @@ carla_autoware 0.0.0 The carla autoware bridge package - Muhammad Raditya Giovanni + Muhammad Raditya GIOVANNI Maxime CLEMENT Apache License 2.0 - ros2launch - ros_compatibility std_msgs autoware_auto_control_msgs autoware_auto_vehicle_msgs - carla_msgs geometry_msgs - nav_msgs rclpy sensor_msgs sensor_msgs_py diff --git a/simulator/carla_autoware/resource/carla_autoware b/simulator/carla_autoware/resource/carla_autoware deleted file mode 100644 index e69de29bb2d1d..0000000000000 diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 223ca5b382dcb..9af250fd40186 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -12,15 +12,14 @@ version="0.0.0", packages=[package_name], data_files=[ - ("share/ament_index/resource_index/packages", ["resource/" + package_name]), ("share/" + package_name, glob("config/objects.json")), ("share/" + package_name, ["package.xml"]), (os.path.join("share", package_name), glob("launch/carla_autoware.launch.xml")), ], install_requires=["setuptools"], zip_safe=True, - maintainer="mradityagio", - maintainer_email="mradityagio@gmail.com", + maintainer="Muhammad Raditya GIOVANNI, Maxime CLEMENT", + maintainer_email="mradityagio@gmail.com, maxime.clement@tier4.jp", description="CARLA ROS2 bridge for AUTOWARE", license="Apache License 2.0", tests_require=["pytest"], diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index 85c1b5d3624da..2e4ae2c30ce86 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -12,13 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License.sr/bin/env python -############################################################## -# Copyright (c) 2018-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -############################################################## - """Modified CARLA Data Provider from CARLA scenario runner.""" from __future__ import print_function From b41ee75c084b2e7175d51e07059d4f1382de35a6 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Tue, 21 May 2024 15:50:30 +0900 Subject: [PATCH 28/50] added max_real_delta_seconds parameter to limit sim speed --- simulator/carla_autoware/README.md | 1 + simulator/carla_autoware/launch/carla_autoware.launch.xml | 2 ++ simulator/carla_autoware/resource/carla_autoware | 0 .../carla_autoware/src/carla_autoware/carla_autoware.py | 8 ++++++++ simulator/carla_autoware/src/carla_autoware/carla_ros.py | 1 + 5 files changed, 12 insertions(+) create mode 100644 simulator/carla_autoware/resource/carla_autoware diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index bcb32ead0f1ac..03d6ae7966bff 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -73,6 +73,7 @@ All the key parameters can be configured in `carla_autoware.launch.xml`. | `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | | `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | | `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | +| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | ### Configurable Parameters for Sensors diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index 588fd3eed515e..f58c5d6f70d6d 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -10,6 +10,7 @@ + @@ -24,6 +25,7 @@ + diff --git a/simulator/carla_autoware/resource/carla_autoware b/simulator/carla_autoware/resource/carla_autoware new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 961b25103ed69..0768fbb90f630 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -60,6 +60,8 @@ def __init__(self): self.world = None self.sensor_wrapper = None self.ego_vehicle = None + self.timestamp_last_run = 0.0 + self.delta_step = 0.0 # Parameter for Initializing Carla World self.local_host = self.param_["host"] @@ -72,6 +74,7 @@ def __init__(self): self.vehicle_type = self.param_["vehicle_type"] self.spawn_point = self.param_["spawn_point"] self.use_traffic_manager = self.param_["use_traffic_manager"] + self.max_real_delta_seconds = self.param_["max_real_delta_seconds"] def load_world(self): client = carla.Client(self.local_host, self.port) @@ -164,6 +167,11 @@ def run_bridge(self): if snapshot: timestamp = snapshot.timestamp if timestamp: + self.delta_step = timestamp.elapsed_seconds - self.timestamp_last_run + if self.delta_step < self.max_real_delta_seconds: + # Add a wait to match the max_real_delta_seconds + time.sleep(self.max_real_delta_seconds - self.delta_step) + self.timestamp_last_run = timestamp.elapsed_seconds self.bridge_loop._tick_sensor(timestamp) def _stop_loop(self, signum, frame): diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 6514eb0e9003f..2587800d793cc 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -94,6 +94,7 @@ def setup(self): "vehicle_type": rclpy.Parameter.Type.STRING, "objects_definition_file": rclpy.Parameter.Type.STRING, "use_traffic_manager": rclpy.Parameter.Type.BOOL, + "max_real_delta_seconds": rclpy.Parameter.Type.DOUBLE, } self.param_values = {} for param_name, param_type in self.parameters.items(): From 651b3a0c0d3794c1dda8b2d01dd48b252a55365b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Wed, 22 May 2024 09:49:23 +0900 Subject: [PATCH 29/50] fix delta step calculation to control the simulation speed Signed-off-by: Maxime CLEMENT --- .../src/carla_autoware/carla_autoware.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 0768fbb90f630..c494092aebd15 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -60,8 +60,7 @@ def __init__(self): self.world = None self.sensor_wrapper = None self.ego_vehicle = None - self.timestamp_last_run = 0.0 - self.delta_step = 0.0 + self.prev_tick_wall_time = 0.0 # Parameter for Initializing Carla World self.local_host = self.param_["host"] @@ -167,11 +166,11 @@ def run_bridge(self): if snapshot: timestamp = snapshot.timestamp if timestamp: - self.delta_step = timestamp.elapsed_seconds - self.timestamp_last_run - if self.delta_step < self.max_real_delta_seconds: + delta_step = time.time() - self.prev_tick_wall_time + if delta_step <= self.max_real_delta_seconds: # Add a wait to match the max_real_delta_seconds - time.sleep(self.max_real_delta_seconds - self.delta_step) - self.timestamp_last_run = timestamp.elapsed_seconds + time.sleep(self.max_real_delta_seconds - delta_step) + self.prev_tick_wall_time = time.time() self.bridge_loop._tick_sensor(timestamp) def _stop_loop(self, signum, frame): From c1077f834018e88c3778dd4218d0268ea57582e4 Mon Sep 17 00:00:00 2001 From: Minsu Kim Date: Thu, 23 May 2024 15:14:04 +0900 Subject: [PATCH 30/50] fix oscillation issue and apply carla's native ackermann control api --- .../src/carla_autoware/carla_autoware.py | 2 +- .../src/carla_autoware/carla_ros.py | 34 ++++++------------- 2 files changed, 12 insertions(+), 24 deletions(-) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index c494092aebd15..b7c1ded0d24a5 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -48,7 +48,7 @@ def _tick_sensor(self, timestamp): ego_action = self.sensor() except SensorReceivedNoData as e: raise RuntimeError(e) - self.ego_vehicle.apply_control(ego_action) + self.ego_vehicle.apply_ackermann_control(ego_action) if self.running: CarlaDataProvider.get_world().tick() diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 2587800d793cc..48cbb365330a5 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -46,7 +46,6 @@ from .modules.carla_utils import carla_rotation_to_ros_quaternion from .modules.carla_utils import create_cloud from .modules.carla_utils import ros_pose_to_carla_transform -from .modules.carla_utils import steer_to_angle_map from .modules.carla_wrapper import SensorInterface @@ -119,7 +118,7 @@ def setup(self): PoseWithCovarianceStamped, "initialpose", self.initialpose_callback, 1 ) - self.current_control = carla.VehicleControl() + self.current_control = carla.VehicleAckermannControl() # Direct data publishing from CARLA for Autoware self.pub_pose_with_cov = self.ros2_node.create_publisher( @@ -378,23 +377,13 @@ def imu(self, carla_imu_measurement): def control_callback(self, in_cmd): """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" - out_cmd = carla.VehicleControl() - self.target_vel = in_cmd.longitudinal.speed - self.vel_diff = self.target_vel - self.current_vel - - if self.vel_diff > 0: - out_cmd.throttle = 0.75 - out_cmd.brake = 0.0 - elif self.vel_diff <= 0.0: - out_cmd.throttle = 0.0 - if self.target_vel <= 0.0: - out_cmd.brake = 0.75 - elif self.vel_diff > -1: - out_cmd.brake = 0.0 - else: - out_cmd.brake = 0.01 - - out_cmd.steer = -in_cmd.lateral.steering_tire_angle + out_cmd = carla.VehicleAckermannControl( + steer=numpy.clip(-math.degrees(in_cmd.lateral.steering_tire_angle)/self.max_steering_angle, -1.0, 1.0), + steer_speed=in_cmd.lateral.steering_tire_rotation_rate, + speed=in_cmd.longitudinal.speed, + acceleration=in_cmd.longitudinal.acceleration, + jerk=in_cmd.longitudinal.jerk + ) self.current_control = out_cmd def ego_status(self): @@ -406,7 +395,6 @@ def ego_status(self): self.param_values["ego_vehicle_role_name"] ) - in_status = ego_vehicle.get_control() self.current_vel = CarlaDataProvider.get_velocity( CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) ) @@ -423,10 +411,10 @@ def ego_status(self): out_vel_state.heading_rate = 0.0 out_steering_state.stamp = out_vel_state.header.stamp - out_steering_state.steering_tire_angle = steer_to_angle_map(self.max_steering_angle)( - in_status.steer + out_steering_state.steering_tire_angle = -math.radians( + ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel) ) - + out_gear_state.stamp = out_vel_state.header.stamp out_gear_state.report = GearReport.DRIVE From c7ea459937bac2c9a6d1ce257408d1e95ab9ed5f Mon Sep 17 00:00:00 2001 From: Minsu Kim Date: Thu, 23 May 2024 15:16:29 +0900 Subject: [PATCH 31/50] fix perception issue by modifying lidar's spawning location --- simulator/carla_autoware/config/objects.json | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index a240b8758321d..5dd9e2035deee 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -21,17 +21,17 @@ "spawn_point": { "x": 0.0, "y": 0.0, - "z": 2.6, + "z": 3.1, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, - "range": 20, - "channels": 32, - "points_per_second": 200000, - "upper_fov": 3.0, - "lower_fov": -27.0, - "rotation_frequency": 20, + "range": 100, + "channels": 64, + "points_per_second": 1200000, + "upper_fov": 10.0, + "lower_fov": -30.0, + "rotation_frequency": 50, "noise_stddev": 0.0 }, { @@ -59,4 +59,4 @@ } } ] -} +} \ No newline at end of file From ce02ef36e938664e1be88ee3d1670f912223a378 Mon Sep 17 00:00:00 2001 From: Minsu Kim Date: Thu, 23 May 2024 15:16:49 +0900 Subject: [PATCH 32/50] sync README.md with the current implementation --- simulator/carla_autoware/README.md | 3 --- 1 file changed, 3 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 03d6ae7966bff..e6464d574ac8c 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -127,7 +127,6 @@ The `carla_ros.py` sets up the CARLA world: ## Tips - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. -- Changing the `fixed_delta_seconds` can increase the simulation tick (default 0.05 s), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). ## Known Issues and Future Works @@ -137,5 +136,3 @@ The `carla_ros.py` sets up the CARLA world: - Sensor currently not automatically configurated to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. - Traffic light recognition. - Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition. -- Ego Vehicle Control. - - Currently during sharp turning the ego-vehicle have large lateral error. From c158aeca200b24c407b0c9966c2646ea8d9f9a2c Mon Sep 17 00:00:00 2001 From: Minsu Kim Date: Thu, 23 May 2024 15:36:20 +0900 Subject: [PATCH 33/50] remove codes that won't be used anymore --- .../src/carla_autoware/modules/carla_utils.py | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py index 9def0c5d87dd1..01f981b53598a 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -108,16 +108,3 @@ def ros_pose_to_carla_transform(ros_pose): carla.Location(ros_pose.position.x, -ros_pose.position.y, ros_pose.position.z), ros_quaternion_to_carla_rotation(ros_pose.orientation), ) - - -def steer_to_angle_map(max_steering_angle): - """Compute the mapping from steering values to corresponding angles.""" - left_steer = -1 - right_steer = 1 - left_angle = np.radians(-max_steering_angle) - right_angle = -left_angle - steer_values = [left_steer, right_steer] - angle_values = [left_angle, right_angle] - coefficients = np.polyfit(steer_values, angle_values, 1) - mapping_function = np.poly1d(coefficients) - return mapping_function From 056458e3e8c56d462ed078590be4dd8d2339a380 Mon Sep 17 00:00:00 2001 From: Minsu Kim Date: Thu, 23 May 2024 16:51:58 +0900 Subject: [PATCH 34/50] revert --- simulator/carla_autoware/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index e6464d574ac8c..8c8839141a730 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -127,6 +127,7 @@ The `carla_ros.py` sets up the CARLA world: ## Tips - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. +- Changing the `fixed_delta_seconds` can increase the simulation tick (default 0.05 s), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS). ## Known Issues and Future Works From 945f5659256da7cb9d72a150a08eb65a442a9bc8 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 23 May 2024 09:19:46 +0000 Subject: [PATCH 35/50] style(pre-commit): autofix --- simulator/carla_autoware/config/objects.json | 2 +- .../carla_autoware/src/carla_autoware/carla_ros.py | 10 +++++++--- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/simulator/carla_autoware/config/objects.json b/simulator/carla_autoware/config/objects.json index 5dd9e2035deee..79d765d8925c2 100644 --- a/simulator/carla_autoware/config/objects.json +++ b/simulator/carla_autoware/config/objects.json @@ -59,4 +59,4 @@ } } ] -} \ No newline at end of file +} diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 48cbb365330a5..53e005200afef 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -378,11 +378,15 @@ def imu(self, carla_imu_measurement): def control_callback(self, in_cmd): """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" out_cmd = carla.VehicleAckermannControl( - steer=numpy.clip(-math.degrees(in_cmd.lateral.steering_tire_angle)/self.max_steering_angle, -1.0, 1.0), + steer=numpy.clip( + -math.degrees(in_cmd.lateral.steering_tire_angle) / self.max_steering_angle, + -1.0, + 1.0, + ), steer_speed=in_cmd.lateral.steering_tire_rotation_rate, speed=in_cmd.longitudinal.speed, acceleration=in_cmd.longitudinal.acceleration, - jerk=in_cmd.longitudinal.jerk + jerk=in_cmd.longitudinal.jerk, ) self.current_control = out_cmd @@ -414,7 +418,7 @@ def ego_status(self): out_steering_state.steering_tire_angle = -math.radians( ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel) ) - + out_gear_state.stamp = out_vel_state.header.stamp out_gear_state.report = GearReport.DRIVE From ec7e920f2a6becc12c8bba7953aecf23dd857093 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 31 May 2024 08:54:54 +0900 Subject: [PATCH 36/50] change control to actuation --- .../calibration_maps/accel_map.csv | 7 ++++ .../calibration_maps/brake_map.csv | 10 +++++ .../calibration_maps/steer_map.csv | 4 ++ .../raw_vehicle_cmd_converter.param.yaml | 28 ++++++++++++++ .../launch/carla_autoware.launch.xml | 1 - simulator/carla_autoware/setup.py | 5 ++- .../src/carla_autoware/carla_autoware.py | 4 +- .../src/carla_autoware/carla_ros.py | 38 +++++++++++-------- 8 files changed, 76 insertions(+), 21 deletions(-) create mode 100644 simulator/carla_autoware/calibration_maps/accel_map.csv create mode 100644 simulator/carla_autoware/calibration_maps/brake_map.csv create mode 100644 simulator/carla_autoware/calibration_maps/steer_map.csv create mode 100644 simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml diff --git a/simulator/carla_autoware/calibration_maps/accel_map.csv b/simulator/carla_autoware/calibration_maps/accel_map.csv new file mode 100644 index 0000000000000..18718c31df87e --- /dev/null +++ b/simulator/carla_autoware/calibration_maps/accel_map.csv @@ -0,0 +1,7 @@ +default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89 +0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500 +0.100,0.167,0.166,-0.093,-0.243,-0.244,-0.245,-0.246,-0.247,-0.248,-0.249,-0.280 +0.200,0.941,0.464,0.186,0.004,-0.100,-0.101,-0.102,-0.103,-0.104,-0.105,-0.106 +0.300,1.747,1.332,0.779,0.778,0.777,0.776,0.775,0.774,0.720,0.640,0.580 +0.400,2.650,2.480,2.300,2.130,1.950,1.750,1.580,1.450,1.320,1.200,1.100 +0.500,3.300,3.250,3.120,2.920,2.680,2.350,2.170,1.980,1.880,1.730,1.610 diff --git a/simulator/carla_autoware/calibration_maps/brake_map.csv b/simulator/carla_autoware/calibration_maps/brake_map.csv new file mode 100644 index 0000000000000..62b18b45bd415 --- /dev/null +++ b/simulator/carla_autoware/calibration_maps/brake_map.csv @@ -0,0 +1,10 @@ +default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89 +0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500 +0.100,0.089,-0.226,-0.535,-0.536,-0.537,-0.538,-0.539,-0.540,-0.541,-0.542,-0.543 +0.200,-0.380,-0.414,-0.746,-0.800,-0.820,-0.850,-0.870,-0.890,-0.910,-0.940,-0.960 +0.300,-1.000,-1.040,-1.480,-1.550,-1.570,-1.590,-1.610,-1.630,-1.631,-1.632,-1.633 +0.400,-1.480,-1.500,-1.850,-2.050,-2.100,-2.101,-2.102,-2.103,-2.104,-2.105,-2.106 +0.500,-1.490,-1.510,-1.860,-2.060,-2.110,-2.111,-2.112,-2.113,-2.114,-2.115,-2.116 +0.600,-1.500,-1.520,-1.870,-2.070,-2.120,-2.121,-2.122,-2.123,-2.124,-2.125,-2.126 +0.700,-1.510,-1.530,-1.880,-2.080,-2.130,-2.131,-2.132,-2.133,-2.134,-2.135,-2.136 +0.800,-2.180,-2.200,-2.700,-2.800,-2.900,-2.950,-2.951,-2.952,-2.953,-2.954,-2.955 diff --git a/simulator/carla_autoware/calibration_maps/steer_map.csv b/simulator/carla_autoware/calibration_maps/steer_map.csv new file mode 100644 index 0000000000000..077efb9f9e200 --- /dev/null +++ b/simulator/carla_autoware/calibration_maps/steer_map.csv @@ -0,0 +1,4 @@ +default,-10,0,10 +-1,-0.9,-0.9,-0.9 +0,0,0,0 +1,0.9,0.9,0.9 diff --git a/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml b/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml new file mode 100644 index 0000000000000..6d20cf0e79c3c --- /dev/null +++ b/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml @@ -0,0 +1,28 @@ +/**: + ros__parameters: + csv_path_accel_map: $(find-pkg-share carla_autoware)/accel_map.csv + csv_path_brake_map: $(find-pkg-share carla_autoware)/brake_map.csv + csv_path_steer_map: $(find-pkg-share carla_autoware)/steer_map.csv + convert_accel_cmd: true + convert_brake_cmd: true + convert_steer_cmd: true + use_steer_ff: true + use_steer_fb: true + is_debugging: false + max_throttle: 0.4 + max_brake: 0.8 + max_steer: 1.0 + min_steer: -1.0 + steer_pid: + kp: 150.0 + ki: 15.0 + kd: 0.0 + max: 8.0 + min: -8.0 + max_p: 8.0 + min_p: -8.0 + max_i: 8.0 + min_i: -8.0 + max_d: 0.0 + min_d: 0.0 + invalid_integration_decay: 0.97 diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index f58c5d6f70d6d..e24014640a411 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -29,7 +29,6 @@ - Date: Thu, 30 May 2024 23:58:15 +0000 Subject: [PATCH 37/50] style(pre-commit): autofix --- simulator/carla_autoware/setup.py | 2 +- simulator/carla_autoware/src/carla_autoware/carla_autoware.py | 2 +- simulator/carla_autoware/src/carla_autoware/carla_ros.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 8b1564b425cb1..7b3f2f95e03b7 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -28,4 +28,4 @@ "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], }, package_dir={"": "src"}, -) \ No newline at end of file +) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 9aa47a4d3560f..c494092aebd15 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -197,4 +197,4 @@ def main(): if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 244a2c183347f..c5328e7045a62 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -461,4 +461,4 @@ def run_step(self, input_data, timestamp): # Publish ego vehicle status self.ego_status() - return self.current_control \ No newline at end of file + return self.current_control From bf0a4b00cd91972df1634b6a879ab759b5fa36b7 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Fri, 31 May 2024 17:08:19 +0900 Subject: [PATCH 38/50] fix steering and small cleanup of the interface Signed-off-by: Maxime CLEMENT --- .../raw_vehicle_cmd_converter.param.yaml | 2 +- .../launch/carla_autoware.launch.xml | 88 ++++++---- .../src/carla_autoware/carla_autoware.py | 156 +++++++++--------- .../src/carla_autoware/carla_ros.py | 75 +++++---- 4 files changed, 169 insertions(+), 152 deletions(-) diff --git a/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml b/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml index 6d20cf0e79c3c..48fd451c3a8f9 100644 --- a/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml +++ b/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml @@ -5,7 +5,7 @@ csv_path_steer_map: $(find-pkg-share carla_autoware)/steer_map.csv convert_accel_cmd: true convert_brake_cmd: true - convert_steer_cmd: true + convert_steer_cmd: false use_steer_ff: true use_steer_fb: true is_debugging: false diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index e24014640a411..ed38e2278239e 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -1,40 +1,56 @@ - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index c494092aebd15..f12ced6900e58 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -26,15 +26,14 @@ class SensorLoop(object): - def __init__(self, role_name): + def __init__(self): self.start_game_time = None self.start_system_time = None self.sensor = None - self.ego_vehicle = None + self.ego_actor = None self.running = False self.timestamp_last_run = 0.0 self.timeout = 20.0 - self.role_name = role_name def _stop_loop(self): self.running = False @@ -48,7 +47,7 @@ def _tick_sensor(self, timestamp): ego_action = self.sensor() except SensorReceivedNoData as e: raise RuntimeError(e) - self.ego_vehicle.apply_control(ego_action) + self.ego_actor.apply_control(ego_action) if self.running: CarlaDataProvider.get_world().tick() @@ -59,7 +58,7 @@ def __init__(self): self.param_ = self.interface.get_param() self.world = None self.sensor_wrapper = None - self.ego_vehicle = None + self.ego_actor = None self.prev_tick_wall_time = 0.0 # Parameter for Initializing Carla World @@ -80,83 +79,78 @@ def load_world(self): client.set_timeout(self.timeout) client.load_world(self.carla_map) self.world = client.get_world() - if self.world is not None: - settings = self.world.get_settings() - settings.fixed_delta_seconds = self.fixed_delta_seconds - settings.synchronous_mode = self.sync_mode - self.world.apply_settings(settings) - CarlaDataProvider.set_world(self.world) - CarlaDataProvider.set_client(client) - spawn_point = carla.Transform() - spawn_point = carla.Transform() - point_items = self.spawn_point.split(",") - randomize = False - if len(point_items) == 6: - spawn_point.location.x = float(point_items[0]) - spawn_point.location.y = float(point_items[1]) - spawn_point.location.z = ( - float(point_items[2]) + 2 - ) # +2 is used so the car did not stuck on the road when spawned. - spawn_point.rotation.roll = float(point_items[3]) - spawn_point.rotation.pitch = float(point_items[4]) - spawn_point.rotation.yaw = float(point_items[5]) - else: - randomize = True - CarlaDataProvider.request_new_actor( - self.vehicle_type, spawn_point, self.agent_role_name, random_location=randomize - ) - - self.sensor_wrapper = SensorWrapper(self.interface) - self.ego_vehicle = CarlaDataProvider.get_actor_by_name(self.agent_role_name) - self.sensor_wrapper.setup_sensors(self.ego_vehicle, False) - ########################################################################################################################################################## - # TRAFFIC MANAGER - ########################################################################################################################################################## - if self.use_traffic_manager: - traffic_manager = client.get_trafficmanager() - traffic_manager.set_synchronous_mode(True) - traffic_manager.set_random_device_seed(0) - random.seed(0) - spawn_points_tm = self.world.get_map().get_spawn_points() - for i, spawn_point in enumerate(spawn_points_tm): - self.world.debug.draw_string(spawn_point.location, str(i), life_time=10) - models = [ - "dodge", - "audi", - "model3", - "mini", - "mustang", - "lincoln", - "prius", - "nissan", - "crown", - "impala", - ] - blueprints = [] - for vehicle in self.world.get_blueprint_library().filter("*vehicle*"): - if any(model in vehicle.id for model in models): - blueprints.append(vehicle) - max_vehicles = 30 - max_vehicles = min([max_vehicles, len(spawn_points_tm)]) - vehicles = [] - for i, spawn_point in enumerate(random.sample(spawn_points_tm, max_vehicles)): - temp = self.world.try_spawn_actor(random.choice(blueprints), spawn_point) - if temp is not None: - vehicles.append(temp) - - for vehicle in vehicles: - vehicle.set_autopilot(True) - + settings = self.world.get_settings() + settings.fixed_delta_seconds = self.fixed_delta_seconds + settings.synchronous_mode = self.sync_mode + self.world.apply_settings(settings) + CarlaDataProvider.set_world(self.world) + CarlaDataProvider.set_client(client) + spawn_point = carla.Transform() + point_items = self.spawn_point.split(",") + randomize = False + if len(point_items) == 6: + spawn_point.location.x = float(point_items[0]) + spawn_point.location.y = float(point_items[1]) + spawn_point.location.z = ( + float(point_items[2]) + 2 + ) # +2 is used so the car did not stuck on the road when spawned. + spawn_point.rotation.roll = float(point_items[3]) + spawn_point.rotation.pitch = float(point_items[4]) + spawn_point.rotation.yaw = float(point_items[5]) else: - print("Carla Interface Couldn't find the world, Carla is not Running") + randomize = True + self.ego_actor = CarlaDataProvider.request_new_actor( + self.vehicle_type, spawn_point, self.agent_role_name, random_location=randomize + ) + self.interface.ego_actor = self.ego_actor # TODO improve design + self.interface.physics_control = self.ego_actor.get_physics_control() + + self.sensor_wrapper = SensorWrapper(self.interface) + self.sensor_wrapper.setup_sensors(self.ego_actor, False) + ########################################################################################################################################################## + # TRAFFIC MANAGER + ########################################################################################################################################################## + if self.use_traffic_manager: + traffic_manager = client.get_trafficmanager() + traffic_manager.set_synchronous_mode(True) + traffic_manager.set_random_device_seed(0) + random.seed(0) + spawn_points_tm = self.world.get_map().get_spawn_points() + for i, spawn_point in enumerate(spawn_points_tm): + self.world.debug.draw_string(spawn_point.location, str(i), life_time=10) + models = [ + "dodge", + "audi", + "model3", + "mini", + "mustang", + "lincoln", + "prius", + "nissan", + "crown", + "impala", + ] + blueprints = [] + for vehicle in self.world.get_blueprint_library().filter("*vehicle*"): + if any(model in vehicle.id for model in models): + blueprints.append(vehicle) + max_vehicles = 30 + max_vehicles = min([max_vehicles, len(spawn_points_tm)]) + vehicles = [] + for i, spawn_point in enumerate(random.sample(spawn_points_tm, max_vehicles)): + temp = self.world.try_spawn_actor(random.choice(blueprints), spawn_point) + if temp is not None: + vehicles.append(temp) + + for vehicle in vehicles: + vehicle.set_autopilot(True) def run_bridge(self): - self.bridge_loop = SensorLoop(self.agent_role_name) + self.bridge_loop = SensorLoop() self.bridge_loop.sensor = self.sensor_wrapper - self.bridge_loop.ego_vehicle = self.ego_vehicle + self.bridge_loop.ego_actor = self.ego_actor self.bridge_loop.start_system_time = time.time() self.bridge_loop.start_game_time = GameTime.get_time() - self.bridge_loop.role_name = self.agent_role_name self.bridge_loop.running = True while self.bridge_loop.running: timestamp = None @@ -179,20 +173,20 @@ def _stop_loop(self, signum, frame): def _cleanup(self): self.sensor_wrapper.cleanup() CarlaDataProvider.cleanup() - if self.ego_vehicle: - self.ego_vehicle.destroy() - self.ego_vehicle = None + if self.ego_actor: + self.ego_actor.destroy() + self.ego_actor = None if self.interface: + self.interface.shutdown() self.interface = None def main(): carla_bridge = InitializeInterface() carla_bridge.load_world() - stop_bridge = signal.signal(signal.SIGINT, carla_bridge._stop_loop) + signal.signal(signal.SIGINT, carla_bridge._stop_loop) carla_bridge.run_bridge() - signal.signal(signal.SIGINT, stop_bridge) carla_bridge._cleanup() diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index c5328e7045a62..965a707c66cb4 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -53,17 +53,15 @@ class carla_interface(object): def __init__(self): self.sensor_interface = SensorInterface() - self.setup() - - def setup(self): self.timestamp = None + self.ego_actor = None + self.physics_control = None self.channels = 0 self.id_to_sensor_type_map = {} self.id_to_camera_info_map = {} self.cv_bridge = CvBridge() self.first_ = True self.pub_lidar = {} - self.sensor_frequencies = { "top": 11, "left": 11, @@ -73,7 +71,6 @@ def setup(self): "status": 50, "pose": 2, } - self.max_steering_angle = 45 self.publish_prev_times = { sensor: datetime.datetime.now() for sensor in self.sensor_frequencies } @@ -140,7 +137,7 @@ def setup(self): self.pub_gear_state = self.ros2_node.create_publisher( GearReport, "/vehicle/status/gear_status", 1 ) - self.actuation_status = self.ros2_node.create_publisher( + self.pub_actuation_status = self.ros2_node.create_publisher( ActuationStatusStamped, "/vehicle/status/actuation_status", 1 ) @@ -229,23 +226,13 @@ def lidar(self, carla_lidar_measurement, id_): point_cloud_msg = create_cloud(header, fields, lidar_data) self.pub_lidar[id_].publish(point_cloud_msg) - def get_ego_vehicle(self): - for car in CarlaDataProvider.get_world().get_actors().filter("vehicle.*"): - if car.attributes["role_name"] == self.agent_role_name: - return car - return None - def initialpose_callback(self, data): """Transform RVIZ initial pose to CARLA.""" - self.ego_vehicle = CarlaDataProvider.get_actor_by_name( - self.param_values["ego_vehicle_role_name"] - ) - pose = data.pose.pose pose.position.z += 2.0 carla_pose_transform = ros_pose_to_carla_transform(pose) - if self.ego_vehicle is not None: - self.ego_vehicle.set_transform(carla_pose_transform) + if self.ego_actor is not None: + self.ego_actor.set_transform(carla_pose_transform) else: print("Can't find Ego Vehicle") @@ -382,7 +369,17 @@ def control_callback(self, in_cmd): """Convert and publish CARLA Ego Vehicle Control to AUTOWARE.""" out_cmd = carla.VehicleControl() out_cmd.throttle = in_cmd.actuation.accel_cmd - out_cmd.steer = -in_cmd.actuation.steer_cmd + # convert base on steer curve of the vehicle + steer_curve = self.physics_control.steering_curve + current_vel = self.ego_actor.get_velocity() + max_steer_ratio = numpy.interp( + abs(current_vel.x), [v.x for v in steer_curve], [v.y for v in steer_curve] + ) + out_cmd.steer = ( + -in_cmd.actuation.steer_cmd + * max_steer_ratio + * math.radians(self.physics_control.wheels[0].max_steer_angle) + ) out_cmd.brake = in_cmd.actuation.brake_cmd self.current_control = out_cmd @@ -390,15 +387,21 @@ def ego_status(self): """Publish ego vehicle status.""" if self.checkFrequency("status"): return + self.publish_prev_times["status"] = datetime.datetime.now() - ego_vehicle = CarlaDataProvider.get_actor_by_name( - self.param_values["ego_vehicle_role_name"] - ) - control = ego_vehicle.get_control() - self.current_vel = CarlaDataProvider.get_velocity( - CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) - ) + # convert velocity from cartesian to ego frame + trans_mat = numpy.array(self.ego_actor.get_transform().get_matrix()).reshape(4, 4) + rot_mat = trans_mat[0:3, 0:3] + inv_rot_mat = rot_mat.T + vel_vec = numpy.array( + [ + self.ego_actor.get_velocity().x, + self.ego_actor.get_velocity().y, + self.ego_actor.get_velocity().z, + ] + ).reshape(3, 1) + ego_velocity = (inv_rot_mat @ vel_vec).T[0] out_vel_state = VelocityReport() out_steering_state = SteeringReport() @@ -408,13 +411,15 @@ def ego_status(self): out_actuation_status = ActuationStatusStamped() out_vel_state.header = self.get_msg_header(frame_id="base_link") - out_vel_state.longitudinal_velocity = self.current_vel - out_vel_state.lateral_velocity = 0.0 - out_vel_state.heading_rate = 0.0 + out_vel_state.longitudinal_velocity = ego_velocity[0] + out_vel_state.lateral_velocity = ego_velocity[1] + out_vel_state.heading_rate = ( + self.ego_actor.get_transform().transform_vector(self.ego_actor.get_angular_velocity()).z + ) out_steering_state.stamp = out_vel_state.header.stamp out_steering_state.steering_tire_angle = -math.radians( - ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel) + self.ego_actor.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel) ) out_gear_state.stamp = out_vel_state.header.stamp @@ -423,14 +428,13 @@ def ego_status(self): out_ctrl_mode.stamp = out_vel_state.header.stamp out_ctrl_mode.mode = ControlModeReport.AUTONOMOUS + control = self.ego_actor.get_control() out_actuation_status.header = self.get_msg_header(frame_id="base_link") out_actuation_status.status.accel_status = control.throttle out_actuation_status.status.brake_status = control.brake - out_actuation_status.status.steer_status = -math.radians( - ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel) - ) + out_actuation_status.status.steer_status = -control.steer - self.actuation_status.publish(out_actuation_status) + self.pub_actuation_status.publish(out_actuation_status) self.pub_vel_state.publish(out_vel_state) self.pub_steering_state.publish(out_steering_state) self.pub_ctrl_mode.publish(out_ctrl_mode) @@ -462,3 +466,6 @@ def run_step(self, input_data, timestamp): # Publish ego vehicle status self.ego_status() return self.current_control + + def shutdown(self): + self.ros2_node.destroy_node() From d1dd300a820a42561a273b17ff371a64a27fb5cb Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Fri, 31 May 2024 18:11:46 +0900 Subject: [PATCH 39/50] Minor cleanup Signed-off-by: Maxime CLEMENT --- .../src/carla_autoware/carla_autoware.py | 4 +-- .../src/carla_autoware/carla_ros.py | 25 +++++++------------ .../src/carla_autoware/modules/carla_utils.py | 1 - 3 files changed, 11 insertions(+), 19 deletions(-) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index f12ced6900e58..8741c33b091e3 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -18,7 +18,7 @@ import carla -from .carla_ros import carla_interface +from .carla_ros import carla_ros2_interface from .modules.carla_data_provider import CarlaDataProvider from .modules.carla_data_provider import GameTime from .modules.carla_wrapper import SensorReceivedNoData @@ -54,7 +54,7 @@ def _tick_sensor(self, timestamp): class InitializeInterface(object): def __init__(self): - self.interface = carla_interface() + self.interface = carla_ros2_interface() self.param_ = self.interface.get_param() self.world = None self.sensor_wrapper = None diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 965a707c66cb4..2379fe838fcbd 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -13,7 +13,6 @@ # limitations under the License.sr/bin/env python import json -import logging import math import threading @@ -40,7 +39,6 @@ from tier4_vehicle_msgs.msg import ActuationStatusStamped from transforms3d.euler import euler2quat -from .modules.carla_data_provider import CarlaDataProvider from .modules.carla_data_provider import GameTime from .modules.carla_data_provider import datetime from .modules.carla_utils import carla_location_to_ros_point @@ -50,7 +48,7 @@ from .modules.carla_wrapper import SensorInterface -class carla_interface(object): +class carla_ros2_interface(object): def __init__(self): self.sensor_interface = SensorInterface() self.timestamp = None @@ -77,8 +75,7 @@ def __init__(self): # initialize ros2 node rclpy.init(args=None) - self.ros2_node = rclpy.create_node("carla_interface") - self.logger = logging.getLogger("log") + self.ros2_node = rclpy.create_node("carla_ros2_interface") self.parameters = { "host": rclpy.Parameter.Type.STRING, "port": rclpy.Parameter.Type.INTEGER, @@ -157,13 +154,15 @@ def __init__(self): PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud', 10 ) else: - self.logger.info("Please use Top, Right, or Left as the LIDAR ID") + self.ros2_node.get_logger().info( + "Please use Top, Right, or Left as the LIDAR ID" + ) elif sensor["type"] == "sensor.other.imu": self.pub_imu = self.ros2_node.create_publisher( Imu, "/sensing/imu/tamagawa/imu_raw", 1 ) else: - self.logger.info("No Publisher for this Sensor") + self.ros2_node.get_logger().info("No Publisher for this Sensor") pass self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) @@ -245,15 +244,9 @@ def pose(self): header = self.get_msg_header(frame_id="map") out_pose_with_cov = PoseWithCovarianceStamped() pose_carla = Pose() - pose_carla.position = carla_location_to_ros_point( - CarlaDataProvider.get_transform( - CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) - ).location - ) + pose_carla.position = carla_location_to_ros_point(self.ego_actor.get_transform().location) pose_carla.orientation = carla_rotation_to_ros_quaternion( - CarlaDataProvider.get_transform( - CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"]) - ).rotation + self.ego_actor.get_transform().rotation ) out_pose_with_cov.header = header out_pose_with_cov.pose.pose = pose_carla @@ -461,7 +454,7 @@ def run_step(self, input_data, timestamp): elif sensor_type == "sensor.other.imu": self.imu(data[1]) else: - self.logger.info("No Publisher for [{key}] Sensor") + self.ros2_node.get_logger().info("No Publisher for [{key}] Sensor") # Publish ego vehicle status self.ego_status() diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py index 01f981b53598a..72eb176515f73 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py @@ -6,7 +6,6 @@ import carla from geometry_msgs.msg import Point from geometry_msgs.msg import Quaternion -import numpy as np from sensor_msgs.msg import PointCloud2 from sensor_msgs.msg import PointField from transforms3d.euler import euler2quat From 8fb50a40a071a6049665b04acb6c011ce4a154ed Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 3 Jun 2024 13:07:07 +0900 Subject: [PATCH 40/50] Fixed spelling and added README for map --- simulator/carla_autoware/README.md | 45 ++++++++++--------- simulator/carla_autoware/setup.py | 2 +- .../src/carla_autoware/carla_autoware.py | 3 +- .../src/carla_autoware/carla_ros.py | 1 + .../modules/carla_data_provider.py | 8 ++-- .../carla_autoware/modules/carla_wrapper.py | 4 +- 6 files changed, 34 insertions(+), 29 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index 8c8839141a730..b62cf2edc7d9a 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -1,8 +1,8 @@ # CARLA Autoware -## ROS2/Autoware.universe bridge for CARLA simulator +## ROS 2/Autoware.universe bridge for CARLA simulator -Thanks to for ROS2 Humble support for CARLA Communication. +Thanks to for ROS 2 Humble support for CARLA Communication. This ros package enables communication between Autoware and CARLA for autonomous driving simulation. ## Supported Environment @@ -17,12 +17,12 @@ This ros package enables communication between Autoware and CARLA for autonomous - [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/) - [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) -- [Python Package for CARLA 0.9.15 Ros2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) +- [Python Package for CARLA 0.9.15 ROS 2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04) - Install the wheel using pip. - OR add the egg file to the `PYTHONPATH`. -1. Download maps (y-axis inverted version) to arbitaly location +1. Download maps (y-axis inverted version) to arbitrary location 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) 3. Create `map_projector_info.yaml` on the folder and add `projector_type: local` on the first line. @@ -35,6 +35,7 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ### Run 1. Run carla, change map, spawn object if you need + ```bash cd CARLA @@ -56,24 +57,25 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release The main class responsible for setting up the CARLA world and the ego vehicle is InitializeInterface. The configuration parameters are fetched using the carla_interface. -### Configureable Parameters for World Loading +### Configurable Parameters for World Loading All the key parameters can be configured in `carla_autoware.launch.xml`. -| Name | Type | Default Value | Description | -| ------------------------- | ------ | ----------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `host` | string | "localhost" | Hostname for the CARLA server | -| `port` | int | "2000" | Port number for the CARLA server | -| `timeout` | int | 20 | Timeout for the CARLA client | -| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | -| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | -| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | -| `carla_map` | string | "Town01" | Name of the map to load in CARLA | -| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | -| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | -| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | -| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | -| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | +| Name | Type | Default Value | Description | +| ------------------------- | ------ | ----------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `host` | string | "localhost" | Hostname for the CARLA server | +| `port` | int | "2000" | Port number for the CARLA server | +| `timeout` | int | 20 | Timeout for the CARLA client | +| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | +| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | +| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | +| `carla_map` | string | "Town01" | Name of the map to load in CARLA | +| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | +| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | +| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | +| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | +| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | +| `config_file` | string | "$(find-pkg-share carla_autoware)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | ### Configurable Parameters for Sensors @@ -82,7 +84,6 @@ Below parameters can be configured in `carla_ros.py`. | Name | Type | Default Value | Description | | ------------------------- | ---- | -------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | `self.sensor_frequencies` | dict | {"top": 11, "left": 11, "right": 11, "camera": 11, "imu": 50, "status": 50, "pose": 2} | (line 67) Calculates the time interval since the last publication and checks if this interval meets the minimum required to not exceed the desired frequency. It will only affect ROS publishing frequency not CARLA sensor tick. | -| `self.max_steering_angle` | int | 45 | (Line 74) Maximum steering angle of a vehicle in degrees, used as parameter to compute the mapping from normalized steering input values. | - CARLA sensor parameters can be configured in `config/objects.json`. - For more details regarding the parameters that can be modified in CARLA are explained in [Carla Ref Sensor](https://carla.readthedocs.io/en/latest/ref_sensors/). @@ -100,7 +101,7 @@ The `carla_ros.py` sets up the CARLA world: 2. **Load the Map**: - Map loaded in CALRA world with map according to `carla_map` parameter. + Map loaded in CARLA world with map according to `carla_map` parameter. ```python client.load_world(self.map_name) @@ -134,6 +135,6 @@ The `carla_ros.py` sets up the CARLA world: - Testing on procedural map (Adv Digital Twin). - Currently unable to test it due to failing in the creation of the Adv digital twin map. - Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. - - Sensor currently not automatically configurated to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. + - Sensor currently not automatically configured to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. - Traffic light recognition. - Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition. diff --git a/simulator/carla_autoware/setup.py b/simulator/carla_autoware/setup.py index 7b3f2f95e03b7..7347e651d1d23 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/carla_autoware/setup.py @@ -21,7 +21,7 @@ zip_safe=True, maintainer="Muhammad Raditya GIOVANNI, Maxime CLEMENT", maintainer_email="mradityagio@gmail.com, maxime.clement@tier4.jp", - description="CARLA ROS2 bridge for AUTOWARE", + description="CARLA ROS 2 bridge for AUTOWARE", license="Apache License 2.0", tests_require=["pytest"], entry_points={ diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py index 8741c33b091e3..b9c72d6c137d9 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_autoware.py @@ -110,6 +110,7 @@ def load_world(self): ########################################################################################################################################################## # TRAFFIC MANAGER ########################################################################################################################################################## + # cspell:ignore trafficmanager if self.use_traffic_manager: traffic_manager = client.get_trafficmanager() traffic_manager.set_synchronous_mode(True) @@ -167,7 +168,7 @@ def run_bridge(self): self.prev_tick_wall_time = time.time() self.bridge_loop._tick_sensor(timestamp) - def _stop_loop(self, signum, frame): + def _stop_loop(self, sign, frame): self.bridge_loop._stop_loop() def _cleanup(self): diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 2379fe838fcbd..6ccdf0d841d2c 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -321,6 +321,7 @@ def camera(self, carla_camera_data): dtype=numpy.uint8, buffer=carla_camera_data.raw_data, ) + # cspell:ignore interp bgra img_msg = self.cv_bridge.cv2_to_imgmsg(image_data_array, encoding="bgra8") img_msg.header = self.get_msg_header( frame_id="traffic_light_left_camera/camera_link_changed" diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py index 2e4ae2c30ce86..7d6608585f582 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py @@ -278,7 +278,7 @@ def check_road_length(wp, length: float): road_id, lane_id = wp.road_id, wp.lane_id while True: wps = wp.next(waypoint_separation) - # The same roadid and laneid,judged to be in the same section to be tested + # The same road_id and lane_id,judged to be in the same section to be tested next_wp = None for p in wps: if p.road_id == road_id and p.lane_id == lane_id: @@ -356,6 +356,7 @@ def get_waypoint_by_laneid(lane_num: int): else: return road_lanes[lane - 1] + # cspell:ignore rolename @staticmethod def create_blueprint( model, rolename="scenario", color=None, actor_category="car", attribute_filter=None @@ -379,6 +380,7 @@ def check_attribute_value(blueprint, name, value): return False + # cspell:ignore carlacola carlamotors _actor_blueprint_categories = { "car": "vehicle.tesla.model3", "van": "vehicle.volkswagen.t2", @@ -746,7 +748,7 @@ def remove_actor_by_id(actor_id): @staticmethod def is_sync_mode(): - """Return true if syncronuous mode is used.""" + """Return true if synchronous mode is used.""" return CarlaDataProvider._sync_flag @staticmethod @@ -855,7 +857,7 @@ def get_carla_time(): return GameTime._carla_time @staticmethod - def get_wallclocktime(): + def get_wall_clock_time(): """Return elapsed game time.""" return GameTime._platform_timestamp diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py index 601bb4c8ac2cc..ed036a47ea9fe 100644 --- a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py +++ b/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py @@ -52,7 +52,7 @@ def __call__(self, data): elif isinstance(data, carla.IMUMeasurement): self._parse_imu_cb(data, self._tag) elif isinstance(data, GenericMeasurement): - self._parse_pseudosensor(data, self._tag) + self._parse_pseudo_sensor(data, self._tag) else: logging.error("No callback method for this sensor.") @@ -72,7 +72,7 @@ def _parse_gnss_cb(self, gnss_data, tag): ) self._data_provider.update_sensor(tag, array, gnss_data.frame) - def _parse_pseudosensor(self, package, tag): + def _parse_pseudo_sensor(self, package, tag): self._data_provider.update_sensor(tag, package.data, package.frame) From fdd53661cfdc282395c2a75ddf549bfef0b3a743 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 3 Jun 2024 13:16:30 +0900 Subject: [PATCH 41/50] fixed minor spelling --- simulator/carla_autoware/launch/carla_autoware.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index ed38e2278239e..cdc2cdcdfe160 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -8,7 +8,7 @@ - + From 4b52508d4f91c6cb35ef3191a9e2a09000629cbe Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 17 Jun 2024 12:37:51 +0900 Subject: [PATCH 42/50] fixed new msg naming --- simulator/carla_autoware/README.md | 38 ++++++++++--------- .../launch/carla_autoware.launch.xml | 2 +- .../src/carla_autoware/carla_ros.py | 18 ++++----- 3 files changed, 31 insertions(+), 27 deletions(-) diff --git a/simulator/carla_autoware/README.md b/simulator/carla_autoware/README.md index b62cf2edc7d9a..ec41c4473ea5c 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/carla_autoware/README.md @@ -9,7 +9,7 @@ This ros package enables communication between Autoware and CARLA for autonomous | ubuntu | ros | carla | autoware | | :----: | :----: | :----: | :------: | -| 22.04 | humble | 0.9.15 | 2024.04 | +| 22.04 | humble | 0.9.15 | Main | ## Setup @@ -55,27 +55,31 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ## Inner-workings / Algorithms -The main class responsible for setting up the CARLA world and the ego vehicle is InitializeInterface. The configuration parameters are fetched using the carla_interface. +The `InitializeInterface` class is key to setting up both the CARLA world and the ego vehicle. It fetches configuration parameters through the `carla_autoware.launch.xml`. + +The main simulation loop runs within the `carla_ros2_interface` class. This loop ticks simulation time inside the CARLA simulator at `fixed_delta_seconds` time, where data is received and published as ROS2 messages at frequencies defined in `self.sensor_frequencies`. + +Ego vehicle commands from Autoware are processed through the `autoware_raw_vehicle_cmd_converter`, which calibrates these commands for CARLA. The calibrated commands are then fed directly into CARLA control via `CarlaDataProvider`. ### Configurable Parameters for World Loading All the key parameters can be configured in `carla_autoware.launch.xml`. -| Name | Type | Default Value | Description | -| ------------------------- | ------ | ----------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `host` | string | "localhost" | Hostname for the CARLA server | -| `port` | int | "2000" | Port number for the CARLA server | -| `timeout` | int | 20 | Timeout for the CARLA client | -| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | -| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | -| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | -| `carla_map` | string | "Town01" | Name of the map to load in CARLA | -| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | -| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | -| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | -| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | -| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | -| `config_file` | string | "$(find-pkg-share carla_autoware)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | +| Name | Type | Default Value | Description | +| ------------------------- | ------ | ----------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `host` | string | "localhost" | Hostname for the CARLA server | +| `port` | int | "2000" | Port number for the CARLA server | +| `timeout` | int | 20 | Timeout for the CARLA client | +| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | +| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | +| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | +| `carla_map` | string | "Town01" | Name of the map to load in CARLA | +| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | +| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | +| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | +| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | +| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | +| `config_file` | string | "$(find-pkg-share carla_autoware)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | ### Configurable Parameters for Sensors diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/carla_autoware/launch/carla_autoware.launch.xml index cdc2cdcdfe160..96afc8f6af74f 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/carla_autoware/launch/carla_autoware.launch.xml @@ -35,7 +35,7 @@ - + diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/carla_autoware/src/carla_autoware/carla_ros.py index 6ccdf0d841d2c..91b51855c8500 100644 --- a/simulator/carla_autoware/src/carla_autoware/carla_ros.py +++ b/simulator/carla_autoware/src/carla_autoware/carla_ros.py @@ -16,11 +16,11 @@ import math import threading -from autoware_auto_vehicle_msgs.msg import ControlModeReport -from autoware_auto_vehicle_msgs.msg import GearReport -from autoware_auto_vehicle_msgs.msg import SteeringReport -from autoware_auto_vehicle_msgs.msg import VelocityReport -from autoware_perception_msgs.msg import TrafficSignalArray +from autoware_perception_msgs.msg import TrafficLightGroupArray +from autoware_vehicle_msgs.msg import ControlModeReport +from autoware_vehicle_msgs.msg import GearReport +from autoware_vehicle_msgs.msg import SteeringReport +from autoware_vehicle_msgs.msg import VelocityReport from builtin_interfaces.msg import Time import carla from cv_bridge import CvBridge @@ -120,7 +120,7 @@ def __init__(self): PoseWithCovarianceStamped, "/sensing/gnss/pose_with_covariance", 1 ) self.pub_traffic_signal_info = self.ros2_node.create_publisher( - TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 + TrafficLightGroupArray, "/perception/traffic_light_recognition/traffic_signals", 1 ) self.pub_vel_state = self.ros2_node.create_publisher( VelocityReport, "/vehicle/status/velocity_status", 1 @@ -151,7 +151,7 @@ def __init__(self): elif sensor["type"] == "sensor.lidar.ray_cast": if sensor["id"] in self.sensor_frequencies: self.pub_lidar[sensor["id"]] = self.ros2_node.create_publisher( - PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud', 10 + PointCloud2, "/sensing/lidar/concatenated/pointcloud", 10 ) else: self.ros2_node.get_logger().info( @@ -162,7 +162,7 @@ def __init__(self): Imu, "/sensing/imu/tamagawa/imu_raw", 1 ) else: - self.ros2_node.get_logger().info("No Publisher for this Sensor") + self.ros2_node.get_logger().info(f'No Publisher for {sensor["type"]} Sensor') pass self.spin_thread = threading.Thread(target=rclpy.spin, args=(self.ros2_node,)) @@ -401,7 +401,7 @@ def ego_status(self): out_steering_state = SteeringReport() out_ctrl_mode = ControlModeReport() out_gear_state = GearReport() - out_traffic = TrafficSignalArray() + out_traffic = TrafficLightGroupArray() out_actuation_status = ActuationStatusStamped() out_vel_state.header = self.get_msg_header(frame_id="base_link") From 537df515a8a24c353971a8c4538254df1e406baf Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Mon, 17 Jun 2024 14:54:20 +0900 Subject: [PATCH 43/50] fixed package dependencies --- simulator/carla_autoware/package.xml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/simulator/carla_autoware/package.xml b/simulator/carla_autoware/package.xml index abd665ba7b844..3248b1aa84e07 100644 --- a/simulator/carla_autoware/package.xml +++ b/simulator/carla_autoware/package.xml @@ -8,8 +8,9 @@ Apache License 2.0 std_msgs - autoware_auto_control_msgs - autoware_auto_vehicle_msgs + tier4_vehicle_msgs + autoware_vehicle_msgs + autoware_perception_msgs geometry_msgs rclpy sensor_msgs From abba0d5e311f13aa1a16c78e271a08873dd824c6 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 17 Jun 2024 05:56:32 +0000 Subject: [PATCH 44/50] style(pre-commit): autofix --- simulator/carla_autoware/package.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulator/carla_autoware/package.xml b/simulator/carla_autoware/package.xml index 3248b1aa84e07..4fb51f76d1a0c 100644 --- a/simulator/carla_autoware/package.xml +++ b/simulator/carla_autoware/package.xml @@ -8,15 +8,15 @@ Apache License 2.0 std_msgs - tier4_vehicle_msgs - autoware_vehicle_msgs autoware_perception_msgs + autoware_vehicle_msgs geometry_msgs rclpy sensor_msgs sensor_msgs_py tf2 tf2_ros + tier4_vehicle_msgs ament_cmake From 0f0b21d01a58d742e1c1c87ff156d7e67d6e3391 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Tue, 18 Jun 2024 14:34:24 +0900 Subject: [PATCH 45/50] renamed package to standard --- .../CMakeLists.txt | 2 +- .../README.md | 14 +++++++------- .../calibration_maps/accel_map.csv | 0 .../calibration_maps/brake_map.csv | 0 .../calibration_maps/steer_map.csv | 0 .../config/objects.json | 0 .../config/raw_vehicle_cmd_converter.param.yaml | 6 +++--- .../launch/autoware_carla_interface.launch.xml} | 6 +++--- .../package.xml | 2 +- .../resource/carla_autoware | 0 simulator/autoware_carla_interface/setup.cfg | 4 ++++ .../setup.py | 6 +++--- .../autoware_carla_interface}/carla_autoware.py | 0 .../src/autoware_carla_interface}/carla_ros.py | 0 .../modules/carla_data_provider.py | 0 .../modules/carla_utils.py | 0 .../modules/carla_wrapper.py | 0 simulator/carla_autoware/setup.cfg | 4 ---- 18 files changed, 22 insertions(+), 22 deletions(-) rename simulator/{carla_autoware => autoware_carla_interface}/CMakeLists.txt (94%) rename simulator/{carla_autoware => autoware_carla_interface}/README.md (91%) rename simulator/{carla_autoware => autoware_carla_interface}/calibration_maps/accel_map.csv (100%) rename simulator/{carla_autoware => autoware_carla_interface}/calibration_maps/brake_map.csv (100%) rename simulator/{carla_autoware => autoware_carla_interface}/calibration_maps/steer_map.csv (100%) rename simulator/{carla_autoware => autoware_carla_interface}/config/objects.json (100%) rename simulator/{carla_autoware => autoware_carla_interface}/config/raw_vehicle_cmd_converter.param.yaml (66%) rename simulator/{carla_autoware/launch/carla_autoware.launch.xml => autoware_carla_interface/launch/autoware_carla_interface.launch.xml} (91%) rename simulator/{carla_autoware => autoware_carla_interface}/package.xml (95%) rename simulator/{carla_autoware => autoware_carla_interface}/resource/carla_autoware (100%) create mode 100644 simulator/autoware_carla_interface/setup.cfg rename simulator/{carla_autoware => autoware_carla_interface}/setup.py (74%) rename simulator/{carla_autoware/src/carla_autoware => autoware_carla_interface/src/autoware_carla_interface}/carla_autoware.py (100%) rename simulator/{carla_autoware/src/carla_autoware => autoware_carla_interface/src/autoware_carla_interface}/carla_ros.py (100%) rename simulator/{carla_autoware/src/carla_autoware => autoware_carla_interface/src/autoware_carla_interface}/modules/carla_data_provider.py (100%) rename simulator/{carla_autoware/src/carla_autoware => autoware_carla_interface/src/autoware_carla_interface}/modules/carla_utils.py (100%) rename simulator/{carla_autoware/src/carla_autoware => autoware_carla_interface/src/autoware_carla_interface}/modules/carla_wrapper.py (100%) delete mode 100644 simulator/carla_autoware/setup.cfg diff --git a/simulator/carla_autoware/CMakeLists.txt b/simulator/autoware_carla_interface/CMakeLists.txt similarity index 94% rename from simulator/carla_autoware/CMakeLists.txt rename to simulator/autoware_carla_interface/CMakeLists.txt index 7c02f26024b69..d643b9dad45fe 100644 --- a/simulator/carla_autoware/CMakeLists.txt +++ b/simulator/autoware_carla_interface/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(carla_autoware) +project(autoware_carla_interface) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/simulator/carla_autoware/README.md b/simulator/autoware_carla_interface/README.md similarity index 91% rename from simulator/carla_autoware/README.md rename to simulator/autoware_carla_interface/README.md index ec41c4473ea5c..1d60e831d3790 100644 --- a/simulator/carla_autoware/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -1,4 +1,4 @@ -# CARLA Autoware +# autoware_carla_interface ## ROS 2/Autoware.universe bridge for CARLA simulator @@ -55,15 +55,15 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ## Inner-workings / Algorithms -The `InitializeInterface` class is key to setting up both the CARLA world and the ego vehicle. It fetches configuration parameters through the `carla_autoware.launch.xml`. +The `InitializeInterface` class is key to setting up both the CARLA world and the ego vehicle. It fetches configuration parameters through the `autoware_carla_interface.launch.xml`. -The main simulation loop runs within the `carla_ros2_interface` class. This loop ticks simulation time inside the CARLA simulator at `fixed_delta_seconds` time, where data is received and published as ROS2 messages at frequencies defined in `self.sensor_frequencies`. +The main simulation loop runs within the `carla_ros2_interface` class. This loop ticks simulation time inside the CARLA simulator at `fixed_delta_seconds` time, where data is received and published as ROS 2 messages at frequencies defined in `self.sensor_frequencies`. Ego vehicle commands from Autoware are processed through the `autoware_raw_vehicle_cmd_converter`, which calibrates these commands for CARLA. The calibrated commands are then fed directly into CARLA control via `CarlaDataProvider`. ### Configurable Parameters for World Loading -All the key parameters can be configured in `carla_autoware.launch.xml`. +All the key parameters can be configured in `autoware_carla_interface.launch.xml`. | Name | Type | Default Value | Description | | ------------------------- | ------ | ----------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | @@ -76,10 +76,10 @@ All the key parameters can be configured in `carla_autoware.launch.xml`. | `carla_map` | string | "Town01" | Name of the map to load in CARLA | | `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | | `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | -| `objects_definition_file` | string | "$(find-pkg-share carla_autoware)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | +| `objects_definition_file` | string | "$(find-pkg-share autoware_carla_interface)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | | `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | | `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | -| `config_file` | string | "$(find-pkg-share carla_autoware)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | +| `config_file` | string | "$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | ### Configurable Parameters for Sensors @@ -139,6 +139,6 @@ The `carla_ros.py` sets up the CARLA world: - Testing on procedural map (Adv Digital Twin). - Currently unable to test it due to failing in the creation of the Adv digital twin map. - Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit. - - Sensor currently not automatically configured to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. + - Sensor currently not automatically configured to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`autoware_carla_interface.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached. - Traffic light recognition. - Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition. diff --git a/simulator/carla_autoware/calibration_maps/accel_map.csv b/simulator/autoware_carla_interface/calibration_maps/accel_map.csv similarity index 100% rename from simulator/carla_autoware/calibration_maps/accel_map.csv rename to simulator/autoware_carla_interface/calibration_maps/accel_map.csv diff --git a/simulator/carla_autoware/calibration_maps/brake_map.csv b/simulator/autoware_carla_interface/calibration_maps/brake_map.csv similarity index 100% rename from simulator/carla_autoware/calibration_maps/brake_map.csv rename to simulator/autoware_carla_interface/calibration_maps/brake_map.csv diff --git a/simulator/carla_autoware/calibration_maps/steer_map.csv b/simulator/autoware_carla_interface/calibration_maps/steer_map.csv similarity index 100% rename from simulator/carla_autoware/calibration_maps/steer_map.csv rename to simulator/autoware_carla_interface/calibration_maps/steer_map.csv diff --git a/simulator/carla_autoware/config/objects.json b/simulator/autoware_carla_interface/config/objects.json similarity index 100% rename from simulator/carla_autoware/config/objects.json rename to simulator/autoware_carla_interface/config/objects.json diff --git a/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml b/simulator/autoware_carla_interface/config/raw_vehicle_cmd_converter.param.yaml similarity index 66% rename from simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml rename to simulator/autoware_carla_interface/config/raw_vehicle_cmd_converter.param.yaml index 48fd451c3a8f9..cb604bc686075 100644 --- a/simulator/carla_autoware/config/raw_vehicle_cmd_converter.param.yaml +++ b/simulator/autoware_carla_interface/config/raw_vehicle_cmd_converter.param.yaml @@ -1,8 +1,8 @@ /**: ros__parameters: - csv_path_accel_map: $(find-pkg-share carla_autoware)/accel_map.csv - csv_path_brake_map: $(find-pkg-share carla_autoware)/brake_map.csv - csv_path_steer_map: $(find-pkg-share carla_autoware)/steer_map.csv + csv_path_accel_map: $(find-pkg-share autoware_carla_interface)/accel_map.csv + csv_path_brake_map: $(find-pkg-share autoware_carla_interface)/brake_map.csv + csv_path_steer_map: $(find-pkg-share autoware_carla_interface)/steer_map.csv convert_accel_cmd: true convert_brake_cmd: true convert_steer_cmd: false diff --git a/simulator/carla_autoware/launch/carla_autoware.launch.xml b/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml similarity index 91% rename from simulator/carla_autoware/launch/carla_autoware.launch.xml rename to simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml index 96afc8f6af74f..b6fef5b692cb8 100644 --- a/simulator/carla_autoware/launch/carla_autoware.launch.xml +++ b/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml @@ -9,12 +9,12 @@ - + - + @@ -33,7 +33,7 @@ - + diff --git a/simulator/carla_autoware/package.xml b/simulator/autoware_carla_interface/package.xml similarity index 95% rename from simulator/carla_autoware/package.xml rename to simulator/autoware_carla_interface/package.xml index 4fb51f76d1a0c..136138a0101b0 100644 --- a/simulator/carla_autoware/package.xml +++ b/simulator/autoware_carla_interface/package.xml @@ -1,6 +1,6 @@ - carla_autoware + autoware_carla_interface 0.0.0 The carla autoware bridge package Muhammad Raditya GIOVANNI diff --git a/simulator/carla_autoware/resource/carla_autoware b/simulator/autoware_carla_interface/resource/carla_autoware similarity index 100% rename from simulator/carla_autoware/resource/carla_autoware rename to simulator/autoware_carla_interface/resource/carla_autoware diff --git a/simulator/autoware_carla_interface/setup.cfg b/simulator/autoware_carla_interface/setup.cfg new file mode 100644 index 0000000000000..c749fdbef61a2 --- /dev/null +++ b/simulator/autoware_carla_interface/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/autoware_carla_interface +[install] +install_scripts=$base/lib/autoware_carla_interface diff --git a/simulator/carla_autoware/setup.py b/simulator/autoware_carla_interface/setup.py similarity index 74% rename from simulator/carla_autoware/setup.py rename to simulator/autoware_carla_interface/setup.py index 7347e651d1d23..ebad68ed30e6f 100644 --- a/simulator/carla_autoware/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -5,7 +5,7 @@ ROS_VERSION = int(os.environ["ROS_VERSION"]) -package_name = "carla_autoware" +package_name = "autoware_carla_interface" setup( name=package_name, @@ -15,7 +15,7 @@ ("share/" + package_name, glob("config/*")), ("share/" + package_name, glob("calibration_maps/*.csv")), ("share/" + package_name, ["package.xml"]), - (os.path.join("share", package_name), glob("launch/carla_autoware.launch.xml")), + (os.path.join("share", package_name), glob("launch/autoware_carla_interface.launch.xml")), ], install_requires=["setuptools"], zip_safe=True, @@ -25,7 +25,7 @@ license="Apache License 2.0", tests_require=["pytest"], entry_points={ - "console_scripts": ["carla_autoware = carla_autoware.carla_autoware:main"], + "console_scripts": ["autoware_carla_interface = autoware_carla_interface.autoware_carla_interface:main"], }, package_dir={"": "src"}, ) diff --git a/simulator/carla_autoware/src/carla_autoware/carla_autoware.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_autoware.py similarity index 100% rename from simulator/carla_autoware/src/carla_autoware/carla_autoware.py rename to simulator/autoware_carla_interface/src/autoware_carla_interface/carla_autoware.py diff --git a/simulator/carla_autoware/src/carla_autoware/carla_ros.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py similarity index 100% rename from simulator/carla_autoware/src/carla_autoware/carla_ros.py rename to simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_data_provider.py similarity index 100% rename from simulator/carla_autoware/src/carla_autoware/modules/carla_data_provider.py rename to simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_data_provider.py diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_utils.py similarity index 100% rename from simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py rename to simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_utils.py diff --git a/simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_wrapper.py similarity index 100% rename from simulator/carla_autoware/src/carla_autoware/modules/carla_wrapper.py rename to simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_wrapper.py diff --git a/simulator/carla_autoware/setup.cfg b/simulator/carla_autoware/setup.cfg deleted file mode 100644 index 6ca2d4bdad9a1..0000000000000 --- a/simulator/carla_autoware/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/carla_autoware -[install] -install_scripts=$base/lib/carla_autoware From ca4eae56201e93f4e4b3a086fd5553073e2a0b6e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 18 Jun 2024 05:37:49 +0000 Subject: [PATCH 46/50] style(pre-commit): autofix --- simulator/autoware_carla_interface/README.md | 26 ++++++++++---------- simulator/autoware_carla_interface/setup.py | 4 ++- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/simulator/autoware_carla_interface/README.md b/simulator/autoware_carla_interface/README.md index 1d60e831d3790..9af4ca4212001 100644 --- a/simulator/autoware_carla_interface/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -65,20 +65,20 @@ Ego vehicle commands from Autoware are processed through the `autoware_raw_vehic All the key parameters can be configured in `autoware_carla_interface.launch.xml`. -| Name | Type | Default Value | Description | -| ------------------------- | ------ | ----------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `host` | string | "localhost" | Hostname for the CARLA server | -| `port` | int | "2000" | Port number for the CARLA server | -| `timeout` | int | 20 | Timeout for the CARLA client | -| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | -| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | -| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | -| `carla_map` | string | "Town01" | Name of the map to load in CARLA | -| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | -| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | +| Name | Type | Default Value | Description | +| ------------------------- | ------ | --------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `host` | string | "localhost" | Hostname for the CARLA server | +| `port` | int | "2000" | Port number for the CARLA server | +| `timeout` | int | 20 | Timeout for the CARLA client | +| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle | +| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) | +| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] | +| `carla_map` | string | "Town01" | Name of the map to load in CARLA | +| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA | +| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) | | `objects_definition_file` | string | "$(find-pkg-share autoware_carla_interface)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA | -| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | -| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | +| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA | +| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` | | `config_file` | string | "$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. | ### Configurable Parameters for Sensors diff --git a/simulator/autoware_carla_interface/setup.py b/simulator/autoware_carla_interface/setup.py index ebad68ed30e6f..b1a7d45db4776 100644 --- a/simulator/autoware_carla_interface/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -25,7 +25,9 @@ license="Apache License 2.0", tests_require=["pytest"], entry_points={ - "console_scripts": ["autoware_carla_interface = autoware_carla_interface.autoware_carla_interface:main"], + "console_scripts": [ + "autoware_carla_interface = autoware_carla_interface.autoware_carla_interface:main" + ], }, package_dir={"": "src"}, ) From b2fdb759a250dc7a98c5ca814a7d5c67b07389c4 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 28 Jun 2024 13:52:43 +0900 Subject: [PATCH 47/50] Fixed LIDAR timeout issue --- simulator/autoware_carla_interface/config/objects.json | 8 ++++---- .../src/autoware_carla_interface/carla_ros.py | 8 +------- 2 files changed, 5 insertions(+), 11 deletions(-) diff --git a/simulator/autoware_carla_interface/config/objects.json b/simulator/autoware_carla_interface/config/objects.json index 79d765d8925c2..7103118937548 100644 --- a/simulator/autoware_carla_interface/config/objects.json +++ b/simulator/autoware_carla_interface/config/objects.json @@ -11,8 +11,8 @@ "pitch": 0.0, "yaw": 0.0 }, - "image_size_x": 480, - "image_size_y": 360, + "image_size_x": 1920, + "image_size_y": 1080, "fov": 90.0 }, { @@ -28,10 +28,10 @@ }, "range": 100, "channels": 64, - "points_per_second": 1200000, + "points_per_second": 300000, "upper_fov": 10.0, "lower_fov": -30.0, - "rotation_frequency": 50, + "rotation_frequency": 20, "noise_stddev": 0.0 }, { diff --git a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py index 91b51855c8500..388c21d4ea8b2 100644 --- a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py +++ b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py @@ -16,7 +16,6 @@ import math import threading -from autoware_perception_msgs.msg import TrafficLightGroupArray from autoware_vehicle_msgs.msg import ControlModeReport from autoware_vehicle_msgs.msg import GearReport from autoware_vehicle_msgs.msg import SteeringReport @@ -119,9 +118,6 @@ def __init__(self): self.pub_pose_with_cov = self.ros2_node.create_publisher( PoseWithCovarianceStamped, "/sensing/gnss/pose_with_covariance", 1 ) - self.pub_traffic_signal_info = self.ros2_node.create_publisher( - TrafficLightGroupArray, "/perception/traffic_light_recognition/traffic_signals", 1 - ) self.pub_vel_state = self.ros2_node.create_publisher( VelocityReport, "/vehicle/status/velocity_status", 1 ) @@ -151,7 +147,7 @@ def __init__(self): elif sensor["type"] == "sensor.lidar.ray_cast": if sensor["id"] in self.sensor_frequencies: self.pub_lidar[sensor["id"]] = self.ros2_node.create_publisher( - PointCloud2, "/sensing/lidar/concatenated/pointcloud", 10 + PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud', 10 ) else: self.ros2_node.get_logger().info( @@ -401,7 +397,6 @@ def ego_status(self): out_steering_state = SteeringReport() out_ctrl_mode = ControlModeReport() out_gear_state = GearReport() - out_traffic = TrafficLightGroupArray() out_actuation_status = ActuationStatusStamped() out_vel_state.header = self.get_msg_header(frame_id="base_link") @@ -433,7 +428,6 @@ def ego_status(self): self.pub_steering_state.publish(out_steering_state) self.pub_ctrl_mode.publish(out_ctrl_mode) self.pub_gear_state.publish(out_gear_state) - self.pub_traffic_signal_info.publish(out_traffic) def run_step(self, input_data, timestamp): self.timestamp = timestamp From cdf85f7bc658ef03e82c315a781b447ee6ec33a3 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 12 Jul 2024 14:22:57 +0900 Subject: [PATCH 48/50] added instruction on how to make traffic recognition work and added example --- simulator/autoware_carla_interface/README.md | 17 +++++++++++++++++ .../launch/autoware_carla_interface.launch.xml | 6 ------ .../src/autoware_carla_interface/carla_ros.py | 2 +- 3 files changed, 18 insertions(+), 7 deletions(-) diff --git a/simulator/autoware_carla_interface/README.md b/simulator/autoware_carla_interface/README.md index 9af4ca4212001..a44cb4708b5c3 100644 --- a/simulator/autoware_carla_interface/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -129,6 +129,23 @@ The `carla_ros.py` sets up the CARLA world: CarlaDataProvider.request_new_actor(self.vehicle_type, spawn_point, self.agent_role_name) ``` +## Traffic Light Recognition + +The maps provided by the Carla Simulator ([Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/)) currently lack proper traffic light components for Autoware and have different latitude and longitude coordinates compared to the pointcloud map. To enable traffic light recognition, follow the steps below to modify the maps. + +- Options to Modify the Map + + - A. Create a New Map from Scratch + - Use the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map. + + - B. Modify the Existing Carla Lanelet2 Maps + - Adjust the longitude and latitude of the [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) to align with the PCD (origin). + - Use this [tool](https://github.com/mraditya01/offset_lanelet2/tree/main) to modify the coordinates. + - Snap Lanelet with PCD and add the traffic lights using the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/). + +- When using the Tier4 Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion. +- For reference, an example of Town01 with added traffic lights at one intersection can be downloaded [here](https://drive.google.com/drive/folders/1QFU0p3C8NW71sT5wwdnCKXoZFQJzXfTG?usp=sharing). + ## Tips - Misalignment might occurs during initialization, pressing `init by gnss` button should fix it. diff --git a/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml b/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml index b6fef5b692cb8..bdef2563777fc 100644 --- a/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml +++ b/simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml @@ -46,11 +46,5 @@ - diff --git a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py index 388c21d4ea8b2..469c7094e8bd8 100644 --- a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py +++ b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py @@ -320,7 +320,7 @@ def camera(self, carla_camera_data): # cspell:ignore interp bgra img_msg = self.cv_bridge.cv2_to_imgmsg(image_data_array, encoding="bgra8") img_msg.header = self.get_msg_header( - frame_id="traffic_light_left_camera/camera_link_changed" + frame_id="traffic_light_left_camera/camera_optical_link" ) cam_info = self._camera_info cam_info.header = img_msg.header From bda3830473db7b764d21393ed18928443d5ad126 Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Wed, 17 Jul 2024 15:25:18 +0900 Subject: [PATCH 49/50] fixed setup.py issue --- simulator/autoware_carla_interface/setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/autoware_carla_interface/setup.py b/simulator/autoware_carla_interface/setup.py index b1a7d45db4776..f4bf37db01fb9 100644 --- a/simulator/autoware_carla_interface/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -26,7 +26,7 @@ tests_require=["pytest"], entry_points={ "console_scripts": [ - "autoware_carla_interface = autoware_carla_interface.autoware_carla_interface:main" + "autoware_carla_interface = autoware_carla_interface.carla_autoware:main" ], }, package_dir={"": "src"}, From 11d352c857036dbbf9600bea6ad0ce15a90df4fd Mon Sep 17 00:00:00 2001 From: mraditya01 Date: Fri, 19 Jul 2024 12:42:00 +0900 Subject: [PATCH 50/50] Fixed LIDAR dimension issue --- .../src/autoware_carla_interface/carla_ros.py | 49 ++++++++++++++----- 1 file changed, 38 insertions(+), 11 deletions(-) diff --git a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py index 469c7094e8bd8..a4f8dee7af1a0 100644 --- a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py +++ b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py @@ -191,7 +191,7 @@ def get_msg_header(self, frame_id): return header def lidar(self, carla_lidar_measurement, id_): - """Transform the a received lidar measurement into a ROS point cloud message.""" + """Transform the received lidar measurement into a ROS point cloud message.""" if self.checkFrequency(id_): return self.publish_prev_times[id_] = datetime.datetime.now() @@ -201,24 +201,51 @@ def lidar(self, carla_lidar_measurement, id_): PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), - PointField(name="intensity", offset=12, datatype=PointField.FLOAT32, count=1), - PointField(name="ring", offset=16, datatype=PointField.UINT16, count=1), + PointField(name="intensity", offset=12, datatype=PointField.UINT8, count=1), + PointField(name="return_type", offset=13, datatype=PointField.UINT8, count=1), + PointField(name="channel", offset=14, datatype=PointField.UINT16, count=1), ] - lidar_data = numpy.fromstring(bytes(carla_lidar_measurement.raw_data), dtype=numpy.float32) - lidar_data = numpy.reshape(lidar_data, (int(lidar_data.shape[0] / 4), 4)) - - ring = numpy.empty((0, 1), object) + lidar_data = numpy.frombuffer( + carla_lidar_measurement.raw_data, dtype=numpy.float32 + ).reshape(-1, 4) + intensity = lidar_data[:, 3] + intensity = ( + numpy.clip(intensity, 0, 1) * 255 + ) # CARLA lidar intensity values are between 0 and 1 + intensity = intensity.astype(numpy.uint8).reshape(-1, 1) + + return_type = numpy.zeros((lidar_data.shape[0], 1), dtype=numpy.uint8) + channel = numpy.empty((0, 1), dtype=numpy.uint16) self.channels = self.sensors["sensors"] for i in range(self.channels[1]["channels"]): current_ring_points_count = carla_lidar_measurement.get_point_count(i) - ring = numpy.vstack((ring, numpy.full((current_ring_points_count, 1), i))) - - lidar_data = numpy.hstack((lidar_data, ring)) + channel = numpy.vstack( + (channel, numpy.full((current_ring_points_count, 1), i, dtype=numpy.uint16)) + ) + lidar_data = numpy.hstack((lidar_data[:, :3], intensity, return_type, channel)) lidar_data[:, 1] *= -1 - point_cloud_msg = create_cloud(header, fields, lidar_data) + + dtype = [ + ("x", "f4"), + ("y", "f4"), + ("z", "f4"), + ("intensity", "u1"), + ("return_type", "u1"), + ("channel", "u2"), + ] + + structured_lidar_data = numpy.zeros(lidar_data.shape[0], dtype=dtype) + structured_lidar_data["x"] = lidar_data[:, 0] + structured_lidar_data["y"] = lidar_data[:, 1] + structured_lidar_data["z"] = lidar_data[:, 2] + structured_lidar_data["intensity"] = lidar_data[:, 3].astype(numpy.uint8) + structured_lidar_data["return_type"] = lidar_data[:, 4].astype(numpy.uint8) + structured_lidar_data["channel"] = lidar_data[:, 5].astype(numpy.uint16) + + point_cloud_msg = create_cloud(header, fields, structured_lidar_data) self.pub_lidar[id_].publish(point_cloud_msg) def initialpose_callback(self, data):