Git Product home page Git Product logo

ros-agent's Introduction

ros-agent

This is a co-simulation project of AVP (Automated Valet Parking) based on CARLA and Autoware. Based on ROS2, the ros-agent retrieve sensor data from CARLA and transmit it to Autoware, then Autoware calculates the control command to pass it to CARLA to execute.

demo


Requirements

  • Ubuntu20.04
  • CPU Intel i7 9th or higher
  • RAM 32GB or more
  • GPU 8GB or more

Installation

The overall installation includes four parts:

  • CARLA installation
  • ROS2 installation
  • Autoware installation
  • ros-agent bridge installation

CARLA

Download the specified CARLA version with SUSTC_Parkinglot Map.

ROS2

This project is based on ROS2 galactic. In order to install galactic, please follow the official tutorial.

Autoware

Autoware is the world's leading open-source software project for AD(Autonomous Driving).Autoware includes the necessary functions to drive an autonomous vehicles from localization and object detection to route planning and control.This project use Autoware galactic as the AD stack.

  1. Clone Autoware repository
mkdir ~/ros-agent
cd ~/ros-agent
git clone https://github.com/ROS-Agent/autoware.git -b galactic
  1. Install dependencies using Ansible. You can also install dependecies manually, following this website.
cd ~/ros-agent/autoware
./setup-dev-env.sh
  1. Create the src directory and clone repositories into it.
mkdir src
vcs import src < autoware.repos
  1. Install dependent ROS packages.
rosdep update --include-eol-distros
source /opt/ros/galactic/setup.bash
rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO
  1. Build the workspace.
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release

ROS-Agent bridge

The ROS-Agent brige is the data transmission bridge, which retrieves sensor data from CARLA to pass it to Autoware and receives Autoware control command to pass it to CARLA.

  1. Clone repositories and Maps.
mkdir -p ~/ros-agent/bridge
cd ~/ros-agent/bridge
git clone https://github.com/ROS-Agent/op_bridge.git -b AVP
git clone https://github.com/ROS-Agent/op_agent.git -b AVP
git clone https://github.com/ROS-Agent/scenario_runner.git
git clone https://github.com/ROS-Agent/Maps.git
  1. Replace sensor config and launch files
cd ~/ros-agent/bridge/Maps
sudo mv autoware.launch.xml ~/ros-agent/autoware/src/launcher/autoware_launch/autoware_launch/launch/autoware.launch.xml
sudo mv gnss.launch.xml ~/ros-agent/autoware/src/sensor_kit/sample_sensor_kit_launch/sample_sensor_kit_launch/launch/gnss.launch.xml
sudo mv sensor_kit_calibration.yaml ~/ros-agent/autoware/src/sensor_kit/sample_sensor_kit_launch/sample_sensor_kit_description/config/sensor_kit_calibration.yaml
sudo mv sensors_calibration.yaml ~/ros-agent/autoware/src/sensor_kit/sample_sensor_kit_launch/sample_sensor_kit_description/config/sensors_calibration.yaml
  1. Set environment variables
gedit ~/.bashrc
# Add the following line to the bottom of the file.
export SCENARIO_RUNNER_ROOT=~/ros-agent/bridge/scenario_runner
export LEADERBOARD_ROOT=~/ros-agent/bridge/op_bridge
export TEAM_CODE_ROOT=~/ros-agent/bridge/op_agent
# Save the file and reset the terminal.

Start the Simulation

  1. Open one terminal
cd $CARLA_ROOT
./CarlaUE4.sh
  1. Open another terminal
cd ~/ros-agent/autoware
source ./install/setup.bash
cd ~/ros-agent/bridge/op_bridge/op_scripts
./run_exploration_mode_ros2.sh
  1. Set vehicle initial pose.
  • (1) Click the 2D Pose estimate button in the toolbar
  • (2) In the 3D View pane, click and hold the left-mouse button, and then drag to set the direction for the initial pose, as the following gif image shows.
  1. Set vehicle goal pose and Engage the vehicle, as the following gif image shows.
  • (1) Click the 2D Goal Pose button in the toolbar
  • (2) In the 3D View pane, click and hold the left-mouse button, and then drag to set the direction for the goal pose. If done correctly, you will see a planned path from initial pose to goal pose
  • (3) Click the Engage button in AutowareStatePanel
  1. Enjoy!!

ROS-Agent Architecture

This is a ROS-Agent Architecture which describes data flow of this project.

How to create PCD Map

There are many ways to create PCD Map using CARLA simulation sensor data. In this project, we use the following two ways.

  1. PCL Recorder. This is a CARLA official ROS Package to allows you to create point cloud maps from CARLA maps. Fore more information, please check this webpage.
  2. LIO-SAM(SLAM). This method uses CARLA sensor data(LiDAR, IMU, GNSS) to SLAM. Here is a real-time lidar-inertial odometry SLAM package.

For more information about Map Creation, please check the Autoware Official website tutorial guides.

How to create HD Map

There are also many ways to create HD Map, but in order to satisfy Autoware's HD Map formap(extended Lanelet2), we use the official HD Map Tools Vector Map Builder. Here are some useful information for your reference:

  1. Vector Map Builder official tutorial.
  2. Vector Map Builder short video tutorial.
  3. Map Toolbox for Autoware, a unity package tool.
  4. ASSURE mapping tools. A desktop based tool for viewing, editing and saving road network maps for autonomous vehicle platforms such as Autoware.
  5. OSM map editor JOSM.
  6. Autoware Lanelet2 format details.

Tips Vector Map Builder only supports ascii pcd map and do not support binary pcd map. You can use the pcl_converter command to complete the conversion between the two formats.

pcl_converter -f ascii source.pcd dest.pcd
# if you have some problems, please check whether you have installed `pcl-tools`.
sudo apt install pcl-tools

ROS-Agent Bridge topic interface

Lidar

Topic name Topic type Description
/carla_pointcloud sensor_msgs/msg/PointCloud2 3D Lidar sensor data

Camera

Topic name Topic type Description
/sensing/camera/traffic_light/camera_info sensor_msgs/msg/CameraInfo This message defines meta information for a camera.
/sensing/camera/traffic_light/image_raw sensor_msgs/msg/Image This message contains an uncompressed image

IMU

Topic name Topic type Description
/sensing/imu/tamagawa/imu_raw sensor_msgs/msg/Imu This is a message to hold data from an IMU (Inertial Measurement Unit)

GNSS

Topic name Topic type Description
/sensing/gnss/ublox/nav_sat_fix sensor_msgs/msg/NavSatFix Navigation Satellite fix for any Global Navigation Satellite System

Vehicle Velocity

Topic name Topic type Description
/vehicle/status/velocity_status autoware_auto_vehicle_msgs/msg/VelocityReport Vechilce realtime velocity data

Vehicle SteerAngle

Topic name Topic type Description
/vehicle/status/steering_status autoware_auto_vehicle_msgs/msg/SteeringReport Vechilce realtime steering angle data

Vehicle Control Mode

Topic name Topic type Description
/vehicle/status/control_mode autoware_auto_vehicle_msgs/msg/ControlModeReport Contorl mode includes NO_COMMAND\AUTONOMOUS\AUTONOMOUS_STEER_ONLY\AUTONOMOUS_VELOCITY_ONLY\MANUAL\DISENGAGED\NOT_READY

Control_command

Topic name Topic type Description
/control/command/control_cmd autoware_auto_control_msgs/msg/AckermannControlCommand Lateral and longitudinal control message for Ackermann-style platforms

ros-agent's People

Contributors

ladissonlai avatar

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.