Skip to main content

ROSbot 3 - ROS 2 API

Detailed information about content of rosbot package for ROS2.

ROS API

Available Nodes

🤖🖥️NODEDESCRIPTION
controller_managerController Manager performs two main functions. First, it manages controllers and their required interfaces, handling tasks like loading, activating, deactivating, and unloading. Second, it interacts with hardware components, ensuring access to their interfaces.
controller_manager/controller_manager
ekf_nodeUsed to fuse wheel odometry and IMU data. Parameters are defined in rosbot_bringup/config/ekf.yaml
robot_localization/ekf_node
/gz_bridgeTransmits Gazebo simulation data to the ROS layer
ros_gz_bridge/parameter_bridge
gz_ros_controlResponsible for integrating the ros2_control controller architecture with the Gazebo simulator.
gz_ros2_control/gz_ros2_control
imu_broadcasterThe broadcaster to publish readings of IMU sensors
imu_sensor_broadcaster/imu_sensor_broadcaster
imu_sensor_nodeThe node responsible for subscriptions to IMU data from the hardware
rosbot_hardware_interfaces/rosbot_imu_sensor
joint_state_broadcasterThe broadcaster reads all state interfaces and reports them on specific topics
joint_state_broadcaster/joint_state_broadcaster
laser_filterThis is a filter that removes points in a laser scan inside of a cartesian box
laser_filters/scan_to_scan_filter_chain
robot_state_publisherUses the URDF specified by the parameter robot*description and the joint positions from the topic joint*states to calculate the forward kinematics of the robot and publish the results using tf
robot_state_publisher/robot_state_publisher
rosbot_system_nodeThe node communicating with the hardware responsible for receiving and sending data related to engine control
rosbot_hardware_interfaces/rosbot_system
rosbot_base_controllerThe controller managing a mobile robot with a differential or omni drive (mecanum wheels). Converts speed commands for the robot body to wheel commands for the base. It also calculates odometry based on hardware feedback and shares it.DiffDriveController or MecanumDriveController
diff_drive_controller/diff_drive_controller
rosbot_gz_bridgeTransmits data about the robot between the Gazebo simulator and ROS.
ros_gz_bridge/parameter_bridge
/stm32_nodeNode responsible for communication with hardware.
micro_ros_agent/micro_ros_agent

Available Topics

🤖🖥️TOPICDESCRIPTION
/battery_stateProvides information about the state of the battery.
sensor_msgs/BatteryState
cmd_velSends velocity commands for controlling robot motion.
geometry_msgs/Twist
diagnosticsContains diagnostic information about the robot's systems.
diagnostic_msgs/DiagnosticArray
dynamic_joint_statesPublishes information about the dynamic state of joints.
control_msgs/DynamicJointState
imu_broadcaster/imuBroadcasts IMU (Inertial Measurement Unit) data.
sensor_msgs/Imu
imu_broadcaster/transition_eventSignals transition events in the lifecycle of the IMU broadcaster node.
lifecycle_msgs/TransitionEvent
joint_state_broadcaster/transition_eventIndicates transition events in the lifecycle of the joint state broadcaster node.
lifecycle_msgs/TransitionEvent
joint_statesPublishes information about the state of robot joints.
sensor_msgs/JointState
odometry/filteredPublishes filtered odometry data.
nav_msgs/Odometry
robot_descriptionPublishes the robot's description.
std_msgs/String
rosbot_base_controller/odomProvides odometry data from the base controller of the ROSbot XL.
nav_msgs/Odometry
rosbot_base_controller/transition_eventIndicates transition events in the lifecycle of the ROSbot XL base controller node.
lifecycle_msgs/TransitionEvent
scanPublishes raw laser scan data.
sensor_msgs/LaserScan
scan_filteredPublishes filtered laser scan data.
sensor_msgs/LaserScan
set_poseSets the robot's pose with covariance.
geometry_msgs/PoseWithCovarianceStamped
tfPublishes transformations between coordinate frames over time.
tf2_msgs/TFMessage
tf_staticPublishes static transformations between coordinate frames.
tf2_msgs/TFMessage

Hidden topic:

TOPICDESCRIPTION
/_imu/data_rawraw data image from imu sensor
sensor_msgs/Imu
/_motors_cmddesired speed on each wheel
std_msgs/Float32MultiArray
/_motors_responsesraw data readings from each wheel
sensor_msgs/JointState

Package Description

rosbot

Metapackage that contains dependencies to other repositories. It is also used to define whether simulation dependencies should be used.

rosbot_bringup

The main package responsible for running the physical robot.

Available Launch Files:

  • bringup.launch.py - is responsible for communicating with firmware and activating all logic related to the robot's movement and processing of sensory data.
  • microros.launch.py - establishes connection with the hardware using microROS agent.

rosbot_controller

ROS2 hardware controller for ROSbot. It manages inputs and outputs data from ROS2 control, forwarding it via ROS topics to be read by microROS. The controller.launch.py file loads the robot model defined in rosbot_description along with ROS2 control dependencies from rosbot_hardware_interfaces.

Available Launch Files:

  • controller.launch.py - starts controllers related to ros2_control responsible for driving, communication with imu and joint_states publications

rosbot_description

URDF model used for both simulation and as a source of transforms on physical robot. It was written to be compatible with ROS Industrial and preconfigured for ROS2 control.

Available Launch Files:

  • load_urdf.launch.py - starts controllers related to ros2_control responsible for driving, communication with imu and joint_states publications
  • rviz.launch.py - Launches the ready-made RViz configuration

Main Description Files:

  • rosbot.urdf.xacro - Final configuration of ROSbot.
  • rosbot_xl.urdf.xacro - Final configuration of ROSbot XL.

rosbot_gazebo

Launch files for Gazebo working with ROS2 control.

Available Launch Files:

  • simulations.launch.py - Runs simulations with a defined robot and all sensors on it.
  • spawn_robot.launch.py - Allow to spawn new robot in already running simulation.

rosbot_localization

A package related to the logic responsible for performing sensor fusion.

Available Launch Files:

  • ekf.launch.py - Runs ekf filter which fuse wheel odometry with imu data.

rosbot_utils

A package containing auxiliary filters that integrate simple external packages.

Available Launch Files:

  • laser_filter.launch.py - launch laser filter responsible for filtering out the laser scan points located inside the robot base.