Skip to content

Latest commit

 

History

History
148 lines (113 loc) · 16.4 KB

ROS_API.md

File metadata and controls

148 lines (113 loc) · 16.4 KB

ROSbot XL - Software

Detailed information about content of rosbot_xl package for ROS2.

Package Description

rosbot_xl

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

rosbot_xl_bringup

Package that contains launch, which starts all base functionalities with the microros agent. Also configs for robot_localization and laser_filters are defined there.

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 firmware.

Launch Params:

PARAMETER DESCRIPTION VALUE
camera_model Add camera model to the robot URDF None*
lidar_model Add LiDAR model to the robot URDF None*
include_camera_mount Whether to include camera mount to the robot URDF False
mecanum Whether to use mecanum drive controller, otherwise use diff drive False
namespace Namespace for all topics and tfs ""

*You can check all available options using -s/--show-args flag. (e.g. ros2 launch rosbot_bringup bringup.launch.py -s).

rosbot_xl_controller

ROS2 hardware controller for ROSbot XL. 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_xl_description along with ROS2 control dependencies from rosbot_hardware_interfaces.

rosbot_xl_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 models:

MODEL DESCRIPTION
rosbot_xl Final configuration of rosbot_xl with ability to attach external hardware.
rosbot_xl_base Base of rosbot prepared to be included into preexisting configuration. Meant to be compatible with concept of ROS Industrial ability for manipulators to have interchangeable end effectors.

rosbot_xl_gazebo

Launch files for Ignition Gazebo working with ROS2 control.

Available Launch Files:

  • simulations.launch.py - running a rosbot in Gazebo simulator and simulate all specified sensors.

Launch Params:

PARAMETER DESCRIPTION VALUE
camera_model Add camera model to the robot URDF None*
lidar_model Add LiDAR model to the robot URDF None*
include_camera_mount Whether to include camera mount to the robot URDF False
mecanum Whether to use mecanum drive controller, otherwise use diff drive False
namespace Namespace for all topics and tfs ""
world Path to SDF world file husarion_gz_worlds/
worlds/husarion_world.sdf
headless Run Gazebo Ignition in the headless mode False
robots List of robots that will be spawn in the simulation []**

*You can check all available options using -s/--show-args flag. (e.g. ros2 launch rosbot_bringup bringup.launch.py -s).

**Example of use: robots:='robot1={x: 0.0, y: -1.0}; robot2={x: 1.0, y: -1.0};'

rosbot_xl_utils

This package contains the stable firmware version with the flash script.

ROS API

Available Nodes

NODE DESCRIPTION
~/controller_manager Controller 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_filter_node Used to fuse wheel odometry and IMU data. Parameters are defined in rosbot_xl_bringup/config/ekf.yaml
robot_localization/ekf_node
~/imu_broadcaster The broadcaster to publish readings of IMU sensors
imu_sensor_broadcaster/imu_sensor_broadcaster
~/imu_sensor_node The node responsible for subscriptions to IMU data from the hardware
rosbot_hardware_interfaces/rosbot_imu_sensor
~/joint_state_broadcaster The broadcaster reads all state interfaces and reports them on specific topics
joint_state_broadcaster/joint_state_broadcaster
~/laser_scan_box_filter This is a filter that removes points in a laser scan inside of a cartesian box
laser_filters/scan_to_scan_filter_chain
~/robot_state_publisher Uses 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 via tf
robot_state_publisher/robot_state_publisher
~/rosbot_system_node The node communicating with the hardware responsible for receiving and sending data related to engine control
rosbot_hardware_interfaces/rosbot_system
~/rosbot_xl_base_controller The 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
~/scan_to_scan_filter_chain Node which subscribes to /scan topic and removes all points that are within the robot's footprint (defined by config laser_filter.yaml in rosbot_xl_bringup package). Filtered laser scan is then published on /scan_filtered topic
laser_filters/scan_to_scan_filter_chain
/stm32_node Node enabling communication with Digital Board, it provides the following interface
micro_ros_agent/micro_ros_agent

Available Topics

TOPIC DESCRIPTION
/battery_state provides information about the state of the battery.
sensor_msgs/BatteryState
~/cmd_vel sends velocity commands for controlling robot motion.
geometry_msgs/Twist
/diagnostics contains diagnostic information about the robot's systems.
diagnostic_msgs/DiagnosticArray
~/dynamic_joint_states publishes information about the dynamic state of joints.
control_msgs/DynamicJointState
~/imu_broadcaster/imu broadcasts IMU (Inertial Measurement Unit) data.
sensor_msgs/Imu
~/imu_broadcaster/transition_event signals transition events in the lifecycle of the IMU broadcaster node.
lifecycle_msgs/TransitionEvent
~/joint_state_broadcaster/transition_event indicates transition events in the lifecycle of the joint state broadcaster node.
lifecycle_msgs/TransitionEvent
~/joint_states publishes information about the state of robot joints.
sensor_msgs/JointState
~/laser_scan_box_filter/transition_event signals transition events in the lifecycle of the laser scan box filter node.
lifecycle_msgs/TransitionEvent
~/odometry/filtered publishes filtered odometry data.
nav_msgs/Odometry
~/robot_description publishes the robot's description.
std_msgs/String
~/rosbot_xl_base_controller/odom provides odometry data from the base controller of the ROSbot XL.
nav_msgs/Odometry
~/rosbot_xl_base_controller/transition_event indicates transition events in the lifecycle of the ROSbot XL base controller node.
lifecycle_msgs/TransitionEvent
~/scan publishes raw laser scan data.
sensor_msgs/LaserScan
~/scan_filtered publishes filtered laser scan data.
sensor_msgs/LaserScan
~/set_pose sets the robot's pose with covariance.
geometry_msgs/PoseWithCovarianceStamped
~/tf publishes transformations between coordinate frames over time.
tf2_msgs/TFMessage
~/tf_static publishes static transformations between coordinate frames.
tf2_msgs/TFMessage

Hidden topic:

TOPIC DESCRIPTION
/_imu/data_raw raw data image from imu sensor
sensor_msgs/Imu
/_motors_cmd desired speed on each wheel
std_msgs/Float32MultiArray
/_motors_responses raw data readings from each wheel
sensor_msgs/JointState