Skip to content

Demo details

Detail of the Quick start demo AWSIM-demo.x86_64 simulation.

Overview

AWSIM simulates sensors, vehicles, driving environments, and traffic instead of reality. AWSIM and Autoware are connected by ROS2 only. Each message that is also used in real vehicles is used. Therefore, Autoware can operate without being aware of whether it is a real or simulator.


UI

UI Feature
Camera sensor Preview of traffic light recognition camera sensor output image.
Time scale The timescale of the simulation progress time. 0.5 simulates the simulation at 0.5x speed. (Range : 0.0 ~ 1.0)
Traffic settings Max vehicle count is aximum number of NPC vehicles present in traffic at the same time. Seed is seed value used in random numbers for random traffic.
Follow camera Enable follow camera operation.
Control mode Change the control mode of the ego vehicle. When MANUAL, control input from the device is used; when AUTONOMOUS, control input from ROS2 (Autoware) is used. Since the control input override is simulated as in a real vehicle, the control mode switches to MANUAL when the control mode is AUTONOMOUS and an input is made by a device.
Vehicle information Information about the vehicle.
Vehicle input device Display of the vehicle's active input devices. Can be switched.
UI menu bar Show/hide each UI; scaling of UI; resetting of UI


Vehicle

This vehicle dynamics model was created for Autoware simulation, and assuming that Autoware has already created a gas pedal map, this vehicle dynamics model uses acceleration as an input value. It has the following features.

  • Lexus RX450h 2015
  • Longitudinal control by acceleration (\(\frac{m}{s^2}\)).
  • Lateral control by two-wheel model.
  • Compute pose by physics engine.
  • Mass-spring-damper suspension model.
  • Automatic gear.(P, D, R, N)
  • Effect of gradient resistance.
  • Tire animation and signal light effects.
  • Support for Keyboard input and Logitech G29 steering wheel
  • First order delay of input.

Device input

  • Keyboard
Key Feature
D Switch to move drive gear.
R Switch to move reverse gear.
N Switch to neutral gear.
P Switch to parking gear.
Up arrow Forward acceleration.
Down arrow Reverse acceleration.
Left arrow Left turning.
Right arrow right turning.
1 Turn left blinker on.
2 Turn right blinker on.
3 Turn on hazard lights.
4 Turn off blinker or hazard lights.
  • Logitech G29 steering wheel
Key Feature
Triangle Switch to move drive gear.
Square Switch to move reverse gear.
Circle Switch to neutral gear.
Cross Switch to parking gear.
Throttle pedal Forward acceleration.
Brake pedal Reverse acceleration.
Steering wheel Turning.
Left paddle Turn left blinker on.
Right paddle Turn right blinker on.
R2 Turn on hazard lights.
R3 Turn off blinker or hazard lights.

Control mode

AWSIM vehicle simulates operations that switch between autonomous driving and manual control. Autoware accepts manual steering and pedal control by the driver during Autonomus Driving. This allows the driver to shift from Autoware's Autonomous driving (AUTONOMOUS control mode) to Driver's Manual driving (MANUAL control mode).

stateDiagram-v2
    AUTONOMOUS --> MANUAL : override input
    MANUAL --> AUTONOMOUS : restart autonomous driving

UI allows checking and switching the current control mode.

AUTONOMOUS MANUAL

Info

Control mode can also be changed from Topic.
ros2 service call input/control_mode_request autoware_vehicle_msgs/srv/ControlModeCommand "mode: 1"

The following modes are supported.
- AUTONOMOUS = 1
- MANUAL = 4


Sensor

Demo simulation has a total of four sensors.

  • LiDAR sensor
  • Camera sensor
  • IMU sensor
  • GNSS sensor

LiDAR sensor

Lidar sensor is the component that simulates the LiDAR (Light Detection and Ranging) sensor. LiDAR works by emitting laser beams that bounce off objects in the environment, and then measuring the time it takes for the reflected beams to return, allowing the sensor to create a 3D map of the surroundings. This data is used for object detection, localization, and mapping.

Publish ROS2 topics.

Topic Msg Hz
/sensing/lidar/top/pointcloud_raw sensor_msgs/PointCloud2 10
/sensing/lidar/top/pointcloud_raw_ex sensor_msgs/PointCloud2 10

Camera sensor

Camera sensor is a component that simulates an RGB camera. Autonomous vehicles can be equipped with many cameras used for various purposes. In the current version of AWSIM, the camera is used primarily to provide the image to the traffic light recognition module in Autoware.

Publish ROS2 topics.

Topic Msg Hz
/sensing/camera/traffic_light/camera_info sensor_msgs/CameraInfo 10
/sensing/camera/traffic_light/image_raw sensor_msgs/Image 10

IMU sensor

IMU sensor is a component that simulates an IMU (Inertial Measurement Unit) sensor. Measures acceleration (\({m}/{s^2}\)) and angular velocity (\({rad}/{s}\)) based on the sensor pose.

Publish ROS2 topics.

Topic Msg Hz
/sensing/imu/tamagawa/imu_raw sensor_msgs/Imu 30

GNSS sensor

GNSS sensor is a component which simulates the position of vehicle computed by the Global Navigation Satellite System based on the transformation of the GameObject to which this component is attached. The GNSS sensor outputs the position in the MGRS coordinate system.

Publish ROS2 topics.

Topic Msg Hz
/sensing/gnss/pose geometry_msgs/Pose 1
/sensing/gnss/pose_with_covariance geometry_msgs/PoseWithCovarianceStamped 1


Traffic

Demo simulation simulates random traffic with NPCs driving according to traffic rules. The Traffic settings UI allows you to change the content of the traffic.

  • Max vehicle count : Maximum number of NPC vehicles present in traffic at the same time.
  • Seed : Seed value used in random numbers for random traffic.


Environment

Map for the demo simulation is West Shinjuku Tokyo Japan. Road surfaces, lanes, traffic signals, signs, etc. are reproduced as in reality. For performance, the building is simplified.


Integration sequence

Initialization

  1. AWSIM: After AWSIM-demo launch, start publishing clock, sensor, and report topics. (1,2,3,4)
  2. Autoware: Estimate ego vehicle position from sensor topics. (5)
  3. Autoware: Generate routes for autonomous driving. (6)
  4. Autoware: Waiting for engage (7)

Autonomous driving loop

  1. AWSIM: Publish each Clock, Sensor, and Report topic. (8, 9, 10)
  2. Autoware: Localization, Perception, Plannning, Control. (11)
  3. Autoware: Publish command topic to contol a vehicle (12)
  4. AWSIM: Controlling Ego vehicles based on command topics. (13)

Warning

Note that this is a simplified sequence diagram. The actual ros2 topic is pub/sub asynchronously.

sequenceDiagram
    autonumber
    participant AWSIM
    participant Autoware
    AWSIM->>AWSIM: After AWSIM-demo launch, start publishing topic
    par
        AWSIM->>Autoware: Clock topic
        AWSIM->>Autoware: Sensor topics
        AWSIM->>Autoware: Report topics
    end
    Autoware->>Autoware: Estimate ego vehicle position from sensor topics
    Autoware->>Autoware: Generate routes for autonomous driving
    Autoware->>Autoware: Waiting for engage
    loop
        par
            AWSIM->>Autoware: Clock topic
            AWSIM->>Autoware: Sensor topics
            AWSIM->>Autoware: Report topics
        end
        Autoware->>Autoware: Localization, Perception, Plannning, Control
        Autoware->>AWSIM: Command topics
        AWSIM->>AWSIM: Control ego vehicle
    end
    note over Autoware: Goal

Json configuration

It is possible to do some configurations by specifying the json path when starting AWSIM-demo.x86_64.

  • Sample json.

    {
        "TimeScale": 1.0,
        "TimeSourceType": 4,
        "RandomTrafficSeed": 33,
        "MaxVehicleCount": 10,
        "LogitechG29DevicePath": "/dev/input/event10",
        "EgoPose": {
            "Position": {
                "x": 81381.7265625,
                "y": 49920.1890625,
                "z": 41.57674865722656
            },
            "EulerAngles": {
                "x": 0.0,
                "y": 0.0,
                "z": 35.0
            }
        }
    }
    

    params type feature
    TimeScale float The timescale of the simulation progress time. 0.5 simulates the simulation at 0.5x speed. (Range : 0.0 ~ 1.0)
    TimeSourceType int Time source to be used in the simulation.
    RandomTrafficSeed int Seed value used in random numbers for random traffic.
    MaxVehicleCount int Maximum number of NPC vehicles present in traffic at the same time.
    LogitechG29DevicePath string Device path for Logitech G29 Steering wheel.
    EgoPose.Position vector3 Initial position of ego vehicle.
    EgoPose.EulerAngles vector3 Initial rotation of ego vehicle.
  • Launch command with json path.

    ./AWSIM-demo.x86_64 --json-path <direcotry path>/<config json name>.json
    

    Info

    AWSIM-demo.zip contains sample-config.json


ROS2

Nodes

Two ROS2 nodes are used in AWSIM.

  • AWSIM
  • RGL

AWSIM ros2 pub/sub, with the exception of the pointcloud, will use the AWSIM ros2 node. For performance, the pointcloud topic output from the LiDAR sensor is published from the RGL ros2 node.

Info

You can check ros2 topic list. (Using a terminal with ros2 sourced)

ros2 topic list

Topics

Subscribers

Topic Message type frame_id Hz QoS
/control/command/control_cmd autoware_control_msgs/Control - 60
  • Reliable
  • TransientLocal
  • KeepLast/1
/control/command/gear_cmd autoware_vehicle_msgs/GearCommand - 10
  • Reliable
  • TransientLocal
  • KeepLast/1
/control/command/turn_indicators_cmd autoware_vehicle_msgs/TurnIndicatorsCommand - 10
  • Reliable
  • TransientLocal
  • KeepLast/1
/control/command/hazard_lights_cmd autoware_vehicle_msgs/HazardLightsCommand - 10
  • Reliable
  • TransientLocal
  • KeepLast/1
/control/command/emergency_cmd tier4_vehicle_msgs/VehicleEmergencyStamped - 60
  • Reliable
  • TransientLocal
  • KeepLast/1

Publishers

Topic Message type frame_id Hz QoS
/clock rosgraph_msgs/Clock - 100
  • Best effort
  • Volatile
  • Keep last/1
/sensing/camera/traffic_light/camera_info sensor_msgs/CameraInfo traffic_light_left_camera/camera_link 10
  • Best effort
  • Volatile
  • Keep last/1
/sensing/camera/traffic_light/image_raw sensor_msgs/Image traffic_light_left_camera/camera_link 10
  • Best effort
  • Volatile
  • Keep last/1
/sensing/gnss/pose geometry_msgs/Pose gnss_link 1
  • Reliable
  • Volatile
  • Keep last/1
/sensing/gnss/pose_with_covariance geometry_msgs/PoseWithCovarianceStamped gnss_link 1
  • Reliable
  • Volatile
  • Keep last/1
/sensing/imu/tamagawa/imu_raw sensor_msgs/Imu tamagawa/imu_link 30
  • Reliable
  • Volatile
  • Keep last/1000
/sensing/lidar/top/pointcloud_raw sensor_msgs/PointCloud2 sensor_kit_base_link 10
  • Best effort
  • Volatile
  • Keep last/5
/sensing/lidar/top/pointcloud_raw_ex sensor_msgs/PointCloud2 sensor_kit_base_link 10
  • Best effort
  • Volatile
  • Keep last/5
/vehicle/status/velocity_status autoware_vehicle_msgs/VelocityReport base_line 30
  • Reliable
  • Volatile
  • Keep last/1
/vehicle/status/steering_status autoware_vehicle_msgs/SteeringReport - 30
  • Reliable
  • Volatile
  • Keep last/1
/vehicle/status/control_mode autoware_vehicle_msgs/ControlModeReport - 30
  • Reliable
  • Volatile
  • Keep last/1
/vehicle/status/gear_status autoware_vehicle_msgs/GearReport - 30
  • Reliable
  • Volatile
  • Keep last/1
/vehicle/status/turn_indicators_status autoware_vehicle_msgs/TurnIndicatorsReport - 30
  • Reliable
  • Volatile
  • Keep last/1
/vehicle/status/hazard_lights_status autoware_vehicle_msgs/HazardLightsReport - 30
  • Reliable
  • Volatile
  • Keep last/1
/awsim/ground_truth/vehicle/pose geometry_msgs/PoseStamped base_link 100
  • Reliable
  • Volatile
  • Keep last/1

Service server

Service Message type
input/control_mode_request autoware_vehicle_msgs/srv/ControlModeCommand