The Gem and its build instructions can be found in this repository. The ROS 2 Gem helps to build robotic simulations with ROS 2 / Robot Operating System. For an example of use see Warehouse Demo Project.
You can browse Doxygen-generated documentation on Gem's GitHub page.
The Gem is currently Linux-only and is being tested with ROS 2 Humble on Ubuntu 22.04 as well as ROS 2 Galactic with Ubuntu 20.04.
It is intended to support any modern ROS 2 version, following these priorities:
Currently tested and validated versions / platforms will be detailed in the project repository.
If you have multiple versions installed, make sure
you source the one
you want to use. You can check which version is sourced in your console by checking the value of ROS_DISTRO
environment variable (echo $ROS_DISTRO
).
Please refer to ROS 2 Concepts documentation if you are not familiar with how ROS 2 works.
The Gem creates a ROS 2 node which is directly a part of ROS 2 ecosystem. As such, your simulation will not use any bridges to communicate and is subject to configuration through settings such as Environment Variables. It is truly a part of the ecosystem.
Note that the simulation node is handled through ROS2SystemComponent
- a singleton. However, you are free to create
and use your own nodes if you need more than one.
Typically, you will be creating publishers and subscriptions. This is done through rclcpp API. Example:
auto ros2Node = ROS2Interface::Get()->GetNode();
AZStd::string fullTopic = ROS2Names::GetNamespacedName(GetNamespace(), m_MyTopic);
m_myPublisher = ros2Node->create_publisher<sensor_msgs::msg::PointCloud2>(fullTopic.data(), QoS());
Note that QoS class is a simple wrapper to rclcpp::QoS.
ROS2FrameComponent
is a representation of an interesting physical part of the robot. It handles spatio-temporal
relationship between this part and other frames of reference. It also encapsulates namespaces, which help to distinguish
between different robots and different parts of the robot, such as in case of multiple identical sensors on one robot.
All Sensors and the Robot Control Component require ROS2FrameComponent
.
Sensors are Components deriving from ROS2SensorComponentBase
specialization. They acquire data from the simulated
environment and publish it to ROS 2 domain.
Sensors processing and publishing depends on their base class - ROS2SensorComponentBase
that is specialized using the
type of event source. At this moment, there are two event sources available:
Above sources events are further handled by an adapter that is internal to ROS2SensorComponentBase
. This way an
additional event (adapted event) is provided to synchronize source event signals to specific frequency. If you intend to
add your own sensor, it might be useful to look at how sensors already provided within the Gem are implemented.
Sensors can be fall into one of two categories:
The Gem comes with ROS2RobotControlComponent
, which you can use to move your robot through:
To make use of received command messages, use either AckermannControlComponent
or RigidBodyTwistControlComponent
,
depending on steering type. You can also implement your own control component or use LUA scripting to handle these
commands.
Unless scripting is used, control components should translate ROS 2 commands to events on VehicleInputControlBus
.
These events will be handled by a VehicleModelComponent
if it is present.
You can use tools such as rqt_robot_steering to move your robot with
Twist messages.
RobotControl
is suitable to use with ROS 2 navigation stack.
It is possible to implement your own control mechanisms with this Component.
VehicleModelComponent
serves the purpose of converting inputs such as target velocity, steering or acceleration to
physical forces on parts of a vehicle (robot).
VehicleModel
has a VehicleConfiguration
which is used to define axles, parametrize and assign wheels.
The model requires a WheelControllerComponent
present in each wheel entity. It also uses an implementation
of DriveModel
, which converts vehicle inputs to forces acting on steering elements and wheels.
The only implementation of DriveModel
available at this moment is the SimplifiedDriveModel
. It
uses PID controllers
from control_toolbox package. These controllers are likely not going
to work with default parameters. The user should tune PID parameters manually. They are exposed through
the VehicleModel
component parameters.
The VehicleModel
will handle input events with names "steering" and "accelerate". This means you can add
an InputComponent to the same entity and
define an input map for your input devices (such as keyboard or a game pad) to control the vehicle manually.
To understand how vehicle dynamics works, please refer to the design document and class diagram
You can use tools such as rqt_robot_steering to move your robot with
Twist messages.
RobotControl
is suitable to use with ROS 2 navigation stack.
It is possible to implement your own control mechanisms with this Component.
ROS2SpawnerComponent
handles spawning entities during simulation.
Available spawnables have to be set up as the component's field before the simulation.
User is able to define named spawn points inside the Editor. This can be done by adding ROS2SpawnPointComponent
to a child entity of an entity with ROS2SpawnerComponent
.
During the simulation user can access names of available spawnables and request spawning using ros2 services.
The names of services are /get_available_spawnable_names
and /spawn_entity
respectivly.
GetWorldProperties.srv and SpawnEntity.srv types are used to handle these features.
In order to request defined spawn points names user can use /get_spawn_points_names
service with GetWorldProperties.srv type.
Detailed information about specific spawn point (e.g. pose) can be accessed using /get_spawn_point_info
service with GetModelState.srv type.
All used services types are defined in gazebo_msgs package.
ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity '{name: 'robot', initial_pose: {position:{ x: 4, y: 4, z: 0.2}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}}}'
ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity '{name: 'robot', xml: 'spawn_spot'}'
ros2 service call /get_available_spawnable_names gazebo_msgs/srv/GetWorldProperties
ros2 service call /get_spawn_points_names gazebo_msgs/srv/GetWorldProperties
ros2 service call /get_spawn_point_info gazebo_msgs/srv/GetModelState '{model_name: 'spawn_spot'}'
You can control how simulation time is handled, which affects timestamps on all the data coming from the simulation. ROS2Clock
class captures this behavior and publishes, or not, current time to \clock
topic based on a configuration setting.
To modify the clock type and enable or disable time publishing, either change configuration parameters in the clockconfiguration.setreg
file, which is located in the Registry
directory, or pass a parameter in the console. There are three possible settings for the sources of time:
You can change the clock type via the .setreg
file by changing the value of the ClockType parameter to one of the above. You can also enable or disable time publishing by changing the value of the PublishClock parameter.
You can change the clock type via the console by adding the --regset=
flag to the call to the simulation binary file, e.g:
./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/ClockType=realtime"
You can enable or disable the time publishing in the same way, e.g:
./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/PublishClock=false"
You can modify both parameters in one command, e.g:
./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/ClockType=realtime" --regset="/O3DE/ROS2/PublishClock=false
The ROS 2 Gem will respect your choice of __
sourced__ ROS 2
environment. The Gem comes with a number of ROS 2 packages already included and linked, but you might want to include
additional packages in your project. To do so, use the target_depends_on_ros2
function:
target_depends_on_ros2_packages(<your_target> <ros_package1> <ros_package2>)
in your project's Gem/CMakeLists.txt
.
It could be the case that you need to create new type of sensor publishing a custom message.
Lets assume your project is called MyProject
, the custom message package is called my_sensor_msgs
and ROS 2
workspace
my_ros2_ws
. Take following steps:
~/projects/my_ros2_ws
)source ~/projects/my_ros2_ws/install/setup.bash
.target_depends_on_ros2_packages(MyProject my_sensor_msgs)
in your Gem/CMakeLists.txt
file.MyProject
and use the new messages.Remember to always have your ROS 2 overlay sourced when building and running the project as sourcing provides visibility of ROS 2 package paths.
Some classes with relationships and functions are presented on this diagram. Specific sensor classes (e.g. Lidar) are not included. Some classes are presented in sub-diagrams: