diff --git a/.github/workflows/industrial_ci.yaml b/.github/workflows/industrial_ci.yaml index da4e8fd..c96d356 100644 --- a/.github/workflows/industrial_ci.yaml +++ b/.github/workflows/industrial_ci.yaml @@ -55,7 +55,7 @@ jobs: - name: Leave only ROSbot tests shell: bash - run: | + run: | sed '/if(BUILD_TESTING)/,/endif()/d' src/diff_drive_controller/CMakeLists.txt -i sed '/if(BUILD_TESTING)/,/endif()/d' src/imu_sensor_broadcaster/CMakeLists.txt -i sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i diff --git a/DEV_GUIDE.md b/DEV_GUIDE.md new file mode 100644 index 0000000..b24452d --- /dev/null +++ b/DEV_GUIDE.md @@ -0,0 +1,46 @@ +# Developer guide + +Description of useful tools and good practices to maintain code readability and reliability. + +## Tools + +### pre-commit + +[pre-commit configuration](.pre-commit-config.yaml) prepares plenty of tests helping for developing and contributing. Usage: + +```bash +# install pre-commit +pip install pre-commit + +# initialize pre-commit workspace +pre-commit install + +# manually run pre-commit hooks +pre-commit run -a + +# update revision +pre-commit autoupdate +``` + +After initialization [pre-commit configuration](.pre-commit-config.yaml) will applied on every commit. + +### Run tests + +```bash +# Run tests +colcon test + +# Show results +colcon test-result --verbose +``` + +> [!NOTE] +> Command `colcon test` does not build the code. Remember to build your code after changes. + +### Industrial CI + +Download industrial package from [github](https://github.com/ros-industrial/industrial_ci/) build it and run following command to run industrial_ci tests locally. + +```bash +ros2 run industrial_ci rerun_ci src/ ROS_DISTRO=humble +``` diff --git a/README.md b/README.md index d47bb09..ccd66ba 100644 --- a/README.md +++ b/README.md @@ -2,208 +2,108 @@ ROS2 packages for ROSbot XL -## ROS packages - -### `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. - -### `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. - -### `rosbot_xl_controller` - -ROS2 hardware controller for ROSbot XL. Inputs and outputs data from ROS2 control and forwards it via ROS topic to be read by microros. - -### `rosbot_xl_utils` - -This package contains the stable firmware version with the flash script. - ## ROS API -Available in [ROS_API.md](./ROS_API.md) +You can find ROS API and detailed package description in [ROS_API.md](./ROS_API.md). -## Usage on hardware +## Prepare environment -To run the software on real ROSbot XL, also communication with Digital Board will be necessary. -First update your firmware to make sure that you use the latest version, then run the `micro-ROS` agent. -For detailed instructions refer to the [rosbot_xl_firmware repository](https://github.com/husarion/rosbot_xl_firmware). +1. **Install `ros-dev-tools` and `stm32flash`** (`stm32flash` is not in the ros index and should be installed manually). -## Prepare environment + ```bash + sudo apt-get update + sudo apt-get install -y ros-dev-tools stm32flash + ``` -1. **Install `colcon`, `vsc` and `rosdep`** -``` -sudo apt-get update -sudo apt-get install -y ros-dev-tools stm32flash -``` +2. **Create workspace folder and clone `rosbot_xl_ros` repository.** -2. **Create workspace folder and clone `rosbot_xl_ros` repository:** -``` -mkdir -p ros2_ws/src -cd ros2_ws -git clone https://github.com/husarion/rosbot_xl_ros src/ -``` + ```bash + mkdir -p ros2_ws/src + cd ros2_ws + git clone https://github.com/husarion/rosbot_xl_ros src/ + ``` ### Build and run on hardware 1. **Building** -``` -export HUSARION_ROS_BUILD=hardware - -source /opt/ros/$ROS_DISTRO/setup.bash -vcs import src < src/rosbot_xl/rosbot_xl_hardware.repos + ```bash + export HUSARION_ROS_BUILD=hardware -# Remove tests from micro_ros_msgs -sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i + source /opt/ros/$ROS_DISTRO/setup.bash -rm -r src/rosbot_xl_gazebo + vcs import src < src/rosbot_xl/rosbot_xl_hardware.repos -# Copy only diff_drive_controller and imu_sensor_broadcaster, waits for features from ros2-control -cp -r src/ros2_controllers/diff_drive_controller src/ -cp -r src/ros2_controllers/imu_sensor_broadcaster src/ -rm -rf src/ros2_controllers + # Remove tests from micro_ros_msgs + sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i -# stm32flash is not in the ros index and should be installed manually -sudo apt install stm32flash + rm -r src/rosbot_xl_gazebo -rosdep init -rosdep update --rosdistro $ROS_DISTRO -rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y -colcon build -``` + # Copy only diff_drive_controller and imu_sensor_broadcaster, waits for features from ros2-control + cp -r src/ros2_controllers/diff_drive_controller src/ + cp -r src/ros2_controllers/imu_sensor_broadcaster src/ + rm -rf src/ros2_controllers -> [!NOTE] -> Before starting the software on the robot please make sure that you're using the latest firmware and run the `micro-ROS` agent as described in the [Usage on hardware](#usage-on-hardware) step. + rosdep init + rosdep update --rosdistro $ROS_DISTRO + rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y + colcon build + ``` 2. **Running** -Flash firmware. -```bash -# Get admin permissions to flash firmware -sudo su -source install/setup.bash -ros2 run rosbot_xl_utils flash_firmware -exit -``` - -``` -source install/setup.bash -ros2 launch rosbot_xl_bringup combined.launch.py -``` + ```bash + source install/setup.bash + ros2 launch rosbot_xl_bringup combined.launch.py + ``` + +> [!IMPORTANT] +> Whenever the software version is changed, it is recommended to update the firmware version to ensure that the package version is compatible with the firmware version. +> +> ```bash +> sudo su # Get admin permissions to flash firmware +> source install/setup.bash +> ros2 run rosbot_xl_utils flash_firmware +> exit +> ``` ### Build and run Gazebo simulation 1. **Building** -``` -export HUSARION_ROS_BUILD=simulation - -source /opt/ros/$ROS_DISTRO/setup.bash - -vcs import src < src/rosbot_xl/rosbot_xl_hardware.repos -vcs import src < src/rosbot_xl/rosbot_xl_simulation.repos - -# Remove tests from micro_ros_msgs -sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i - -# Copy only diff_drive_controller and imu_sensor_broadcaster, waits for features from ros2-control -cp -r src/ros2_controllers/diff_drive_controller src/ -cp -r src/ros2_controllers/imu_sensor_broadcaster src/ -rm -rf src/ros2_controllers - -rosdep init -rosdep update --rosdistro $ROS_DISTRO -rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y -colcon build -``` - -2. **Running** -``` -source install/setup.bash -ros2 launch rosbot_xl_gazebo simulation.launch.py -``` -## Testing package - -### pre-commit -[pre-commit configuration](.pre-commit-config.yaml) prepares plenty of tests helping for developing and contributing. Usage: -```bash -# install pre-commit -pip install pre-commit + ```bash + export HUSARION_ROS_BUILD=simulation -# initialize pre-commit workspace -pre-commit install + source /opt/ros/$ROS_DISTRO/setup.bash -# manually run tests -pre-commit run -a + vcs import src < src/rosbot_xl/rosbot_xl_hardware.repos + vcs import src < src/rosbot_xl/rosbot_xl_simulation.repos -# update revision -pre-commit autoupdate -``` + # Remove tests from micro_ros_msgs + sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i -After initialization [pre-commit configuration](.pre-commit-config.yaml) will applied on every commit. + # Copy only diff_drive_controller and imu_sensor_broadcaster, waits for features from ros2-control + cp -r src/ros2_controllers/diff_drive_controller src/ + cp -r src/ros2_controllers/imu_sensor_broadcaster src/ + rm -rf src/ros2_controllers -### Industrial CI -``` -colcon test -``` + rosdep init + rosdep update --rosdistro $ROS_DISTRO + rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y + colcon build + ``` -> [!NOTE] -> Command `colcon test` does not build the code. Remember to build your code after changes. - -If tests finish with errors print logs: -``` -colcon test-result --verbose -``` - -### Format python code with [Black](https://github.com/psf/black) -``` -cd src/ -black rosbot* -``` - - -## Testing package - -### Industrial CI -``` -colcon test -``` - -> [!NOTE] -> Command `colcon test` does not build the code. Remember to build your code after changes. - -If tests finish with errors print logs: -``` -colcon test-result --verbose -``` +2. **Running** -### Format python code with [Black](https://github.com/psf/black) -``` -cd src/ -black rosbot* -``` + ```bash + source install/setup.bash + ros2 launch rosbot_xl_gazebo simulation.launch.py + ``` ## Demos For further usage examples check out our other repositories: + * [`rosbot-xl-docker`](https://github.com/husarion/rosbot-xl-docker) - Dockerfiles for building hardware and simulation images * [`rosbot-xl-gamepad`](https://github.com/husarion/rosbot-xl-gamepad) - simple teleoperation using a gamepad * [`rosbot-xl-mapping`](https://github.com/husarion/rosbot-xl-mapping) - creating a map of the environment using slam_toolbox diff --git a/ROS_API.md b/ROS_API.md index 3cddc39..3e39038 100644 --- a/ROS_API.md +++ b/ROS_API.md @@ -1,47 +1,148 @@ -Use `bringup.launch.py` from `rosbot_xl_bringup` to start all base functionalities for ROSbot XL. It consists of the following parts: -- `scan_to_scan_filter_chain` from `laser_filters`, it 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 +# ROSbot XL - Software - **Subscribes** - - `/scan` (_sensor_msgs/LaserScan_) +Detailed information about content of rosbot_xl package for ROS2. - **Publishes** - - `/scan_filtered` (_sensor_msgs/LaserScan_) +## Package Description -- `ekf_node` from `robot_localization`, it is used to fuse wheel odometry and IMU data. Parameters are defined in `ekf.yaml` in `rosbot_xl_bringup/config`. It subscribes to `/rosbot_xl_base_controller/odom` and `/imu_broadcaster/imu` published by ros2 controllers and publishes fused odometry on `/odometry/filtered` topic +### `rosbot_xl` - **Subscribes** - - `/rosbot_xl_base_controller/odom` (_nav_msgs/Odometry_) - - `/imu_broadcaster/imu` (_sensor_msgs/Imu_) +Metapackage that contains dependencies to other repositories. It is also used to define whether simulation dependencies should be used. - **Publishes** - - `/tf` (_tf2_msgs/TFMessage_) - `base_link`->`odom` transform - - `/odometry/filtered` (_nav_msgs/Odometry_) +### `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. -- `controller.launch.py` from `rosbot_xl_controller`, it loads robot model defined in `rosbot_xl_description` as well as ros2 control [rosbot_hardware_interfaces](https://github.com/husarion/rosbot_hardware_interfaces). It also starts controllers: - * `joint_state_broadcaster` - * `rosbot_xl_base_controller` - depending on the value of `mecanum` argument it can be `DiffDriveController` or `MecanumDriveController` - * `imu_broadcaster` +**Available Launch Files:** - **Subscribes** - - `/cmd_vel` (_geometry_msgs/Twist_) - - `/_motors_responses` (_sensor_msgs/JointState_) - - `/_imu/data_raw` (_sensor_msgs/Imu_) +- `bringup.launch.py` - is responsible for activating all logic related to the robot's movement and processing of sensory data. +- `combined.launch.py` - launches `bringup.launch.py` ​​and communication with the firmware allows you to control the robot. - **Publishes** - - `/tf` (_tf2_msgs/TFMessage_) - - `/tf_static` (_tf2_msgs/TFMessage_) - - `/_motors_cmd` (_std_msgs/Float32MultiArray_) - - `/rosbot_xl_base_controller/odom` (_nav_msgs/Odometry_) - - `/imu_broadcaster/imu` (_sensor_msgs/Imu_) +**Launch Params:** -Use `micro_ros_agent` to communicate with Digital Board, it provides the following interface: +| 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 | **""** | -**Subscribes** -- `/_motors_cmd` (_std_msgs/Float32MultiArray_) +> \*You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_bringup bringup.launch.py -s`). +### `rosbot_xl_controller` -**Publishes** -- `/_motors_responses` (_sensor_msgs/JointState_) -- `/_imu/data_raw` (_sensor_msgs/Imu_) -- `/battery_state` (_sensor_msgs/BatteryState_) +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](https://github.com/husarion/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_office_gz/`
`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 + +[controller_manager/controller_manager]: https://github.com/ros-controls/ros2_control/blob/master/controller_manager +[diff_drive_controller/diff_drive_controller]: https://github.com/ros-controls/ros2_controllers/tree/master/diff_drive_controller +[imu_sensor_broadcaster/imu_sensor_broadcaster]: https://github.com/ros-controls/ros2_controllers/tree/master/imu_sensor_broadcaster +[joint_state_broadcaster/joint_state_broadcaster]: https://github.com/ros-controls/ros2_controllers/tree/master/joint_state_broadcaster +[laser_filters/scan_to_scan_filter_chain]: https://github.com/ros-perception/laser_filters/blob/ros2/src/scan_to_scan_filter_chain.cpp +[micro_ros_agent/micro_ros_agent]: https://github.com/micro-ROS/micro-ROS-Agent +[robot_localization/ekf_node]: https://github.com/cra-ros-pkg/robot_localization +[robot_state_publisher/robot_state_publisher]: https://github.com/ros/robot_state_publisher +[rosbot_hardware_interfaces/rosbot_imu_sensor]: https://github.com/husarion/rosbot_hardware_interfaces/blob/main/src/rosbot_imu_sensor.cpp +[rosbot_hardware_interfaces/rosbot_system]: https://github.com/husarion/rosbot_hardware_interfaces/blob/main/src/rosbot_system.cpp + +| 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 + +[control_msgs/DynamicJointState]: https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/DynamicJointState.msg +[diagnostic_msgs/DiagnosticArray]: https://docs.ros2.org/foxy/api/diagnostic_msgs/msg/DiagnosticArray.html +[geometry_msgs/PoseWithCovarianceStamped]: https://docs.ros2.org/foxy/api/geometry_msgs/msg/PoseWithCovarianceStamped.html +[geometry_msgs/Twist]: https://docs.ros2.org/foxy/api/geometry_msgs/msg/Twist.html +[lifecycle_msgs/TransitionEvent]: https://docs.ros2.org/foxy/api/lifecycle_msgs/msg/TransitionEvent.html +[nav_msgs/Odometry]: https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html +[sensor_msgs/BatteryState]: https://docs.ros2.org/foxy/api/sensor_msgs/msg/BatteryState.html +[sensor_msgs/Imu]: https://docs.ros2.org/foxy/api/sensor_msgs/msg/Imu.html +[sensor_msgs/JointState]: https://docs.ros2.org/foxy/api/sensor_msgs/msg/JointState.html +[sensor_msgs/LaserScan]: https://docs.ros2.org/foxy/api/sensor_msgs/msg/LaserScan.html +[std_msgs/Float32MultiArray]: https://docs.ros2.org/foxy/api/std_msgs/msg/Float32MultiArray.html +[std_msgs/String]: https://docs.ros2.org/foxy/api/std_msgs/msg/String.html +[tf2_msgs/TFMessage]: https://docs.ros2.org/foxy/api/tf2_msgs/msg/TFMessage.html + +| 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][]_ | diff --git a/rosbot_xl_bringup/launch/bringup.launch.py b/rosbot_xl_bringup/launch/bringup.launch.py index 6ac3995..b494e31 100644 --- a/rosbot_xl_bringup/launch/bringup.launch.py +++ b/rosbot_xl_bringup/launch/bringup.launch.py @@ -34,9 +34,7 @@ def generate_launch_description(): declare_mecanum_arg = DeclareLaunchArgument( "mecanum", default_value="False", - description=( - "Whether to use mecanum drive controller (otherwise diff drive controller is used)" - ), + description="Whether to use mecanum drive controller, otherwise use diff drive", ) camera_model = LaunchConfiguration("camera_model") diff --git a/rosbot_xl_bringup/launch/combined.launch.py b/rosbot_xl_bringup/launch/combined.launch.py index 597e0a6..45754ff 100644 --- a/rosbot_xl_bringup/launch/combined.launch.py +++ b/rosbot_xl_bringup/launch/combined.launch.py @@ -81,9 +81,7 @@ def generate_launch_description(): declare_mecanum_arg = DeclareLaunchArgument( "mecanum", default_value="False", - description=( - "Whether to use mecanum drive controller (otherwise diff drive controller is used)" - ), + description="Whether to use mecanum drive controller, otherwise use diff drive", ) camera_model = LaunchConfiguration("camera_model") diff --git a/rosbot_xl_controller/launch/controller.launch.py b/rosbot_xl_controller/launch/controller.launch.py index 47516e5..8cd1510 100644 --- a/rosbot_xl_controller/launch/controller.launch.py +++ b/rosbot_xl_controller/launch/controller.launch.py @@ -122,9 +122,7 @@ def generate_launch_description(): declare_mecanum_arg = DeclareLaunchArgument( "mecanum", default_value="False", - description=( - "Whether to use mecanum drive controller (otherwise diff drive controller is used)", - ), + description="Whether to use mecanum drive controller, otherwise use diff drive", ) camera_model = LaunchConfiguration("camera_model") diff --git a/rosbot_xl_gazebo/launch/simulation.launch.py b/rosbot_xl_gazebo/launch/simulation.launch.py index bf48d40..2d5bbf6 100644 --- a/rosbot_xl_gazebo/launch/simulation.launch.py +++ b/rosbot_xl_gazebo/launch/simulation.launch.py @@ -84,6 +84,11 @@ def launch_setup(context, *args, **kwargs): spawn_group = [] for robot_name in robots_list: init_pose = robots_list[robot_name] + + spawn_log = LogInfo( + msg=[f"Launching namespace={robot_name} with init_pose= {str(init_pose)}"] + ) + spawn_robot = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( @@ -109,18 +114,12 @@ def launch_setup(context, *args, **kwargs): "yaw": TextSubstitution(text=str(init_pose["yaw"])), }.items(), ) + group = GroupAction( - [ - LogInfo( - msg=[ - "Launching namespace=", - robot_name, - " init_pose=", - str(init_pose), - ] - ), + actions=[ + spawn_log, spawn_robot, - ] + ], ) spawn_group.append(group) @@ -137,9 +136,7 @@ def generate_launch_description(): declare_mecanum_arg = DeclareLaunchArgument( "mecanum", default_value="False", - description=( - "Whether to use mecanum drive controller (otherwise diff drive controller is used)" - ), + description="Whether to use mecanum drive controller, otherwise use diff drive", ) declare_camera_model_arg = DeclareLaunchArgument( @@ -183,7 +180,7 @@ def generate_launch_description(): world_package = get_package_share_directory("husarion_office_gz") world_file = PathJoinSubstitution([world_package, "worlds", "husarion_world.sdf"]) declare_world_arg = DeclareLaunchArgument( - "world", default_value=world_file, description="SDF world file" + "world", default_value=world_file, description="Path to SDF world file" ) declare_headless_arg = DeclareLaunchArgument( @@ -196,8 +193,8 @@ def generate_launch_description(): "robots", default_value=[], description=( - "The list of the robots spawned in the simulation e. g. robots:='robot1={x: 0.0, y:" - " -1.0}; robot2={x: 1.0, y: -1.0}; robot3={x: 2.0, y: -1.0}; robot4={x: 3.0, y: -1.0}'" + "List of robots that will be spawn in the simulation e. g. robots:='robot1={x: 0.0, y:" + " -1.0}; robot2={x: 1.0, y: -1.0}; robot3={x: 2.0, y: -1.0}'" ), ) diff --git a/rosbot_xl_gazebo/launch/spawn.launch.py b/rosbot_xl_gazebo/launch/spawn.launch.py index 7ad6cec..e235a61 100644 --- a/rosbot_xl_gazebo/launch/spawn.launch.py +++ b/rosbot_xl_gazebo/launch/spawn.launch.py @@ -177,9 +177,7 @@ def generate_launch_description(): declare_mecanum_arg = DeclareLaunchArgument( "mecanum", default_value="False", - description=( - "Whether to use mecanum drive controller (otherwise diff drive controller is used)" - ), + description="Whether to use mecanum drive controller, otherwise use diff drive", ) camera_model = LaunchConfiguration("camera_model")