From 482a944873f4afbfdf556f2e60e0aed98b0d75bc Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Thu, 5 Dec 2024 10:08:55 +0100 Subject: [PATCH] Update docs --- .pre-commit-config.yaml | 1 + CONTRIBUTING.md | 59 +++++++++++ README.md | 169 ++++++++--------------------- ROS_API.md | 188 +++++++++++++++++++++++++++------ rosbot_description/package.xml | 2 +- rosbot_gazebo/package.xml | 2 +- 6 files changed, 261 insertions(+), 160 deletions(-) create mode 100644 CONTRIBUTING.md diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index d472c928..389b9f0f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -85,6 +85,7 @@ repos: stages: [commit] entry: ament_copyright language: system + exclude: ^.*\.md$ - repo: https://github.com/PyCQA/doc8 rev: v1.1.2 diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000..351e9d40 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,59 @@ +# Developer info and tools + +## USB-A connection + +You can connect to the robot hardware on your own computer. To establish a connection, connect your computer to the robot using a USB-A cable. Then build the code locally and specify via the serial_port argument which processor should be used to establish the connection. + +```bash +ros2 launch rosbot_bringup bringup.launch.py serial_port:=/dev/ttyUSB0 +``` + +The hardware checks the connection via USB-A only during initialization and when btn1 or btn2 is pressed, so while executing the above command, hold down the reset button together with bnt1/bnt2 and release the reset button. After establishing a connection, you can release bnt1/bnt2. + +## 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 tests +pre-commit run -a +``` + +After initialization [pre-commit configuration](.pre-commit-config.yaml) will applied on every commit. + +## Industrial CI + +```bash +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: + +``` bash +colcon test-result --verbose +``` + + +### Testing `.github/workflows/industrial_ci.yaml` Locally + +At fist install [act](https://github.com/nektos/act): + +```bash +cd / +curl -s https://raw.githubusercontent.com/nektos/act/master/install.sh | sudo bash +``` + +And test the workflow with: + +```bash +act -W .github/workflows/industrial_ci.yaml +``` diff --git a/README.md b/README.md index b6a697b9..5706c732 100644 --- a/README.md +++ b/README.md @@ -1,61 +1,35 @@ # Rosbot ROS -ROS2 packages for ROSbot 2R and ROSbot 2 PRO. +ROS 2 packages for Husarion ROSbot series. -## ROS packages +![ROSbot](https://husarion.com/assets/images/2r_colour_perspective-14e3679e451eb9fe4e79eeecf7b82e65.png) -### `rosbot` +## 📚 ROS API -Metapackage that contains dependencies to other repositories. +Documentation is available in ROS_API.md. -### `rosbot_bringup` +## 🚀 Quick Start -Package that contains launch, which starts all base functionalities. Also configuration for [robot_localization](https://github.com/cra-ros-pkg/robot_localization) and [ros2_controllers](https://github.com/ros-controls/ros2_controllers) are defined there. +### ⚙ī¸ Prerequisites -### `rosbot_description` +1. Install all necessary tools: -URDF model used as a source of transforms on the physical robot. It was written to be compatible with ROS Industrial and preconfigured for ROS2 control. + ```bash + sudo apt-get update + sudo apt-get install -y python3-pip ros-dev-tools stm32flash + ``` -### `rosbot_gazebo` +2. Create a workspace folder and clone the rosbot_ros repository: -Launch files for Ignition Gazebo working with ROS2 control. + ```bash + mkdir -p ros2_ws + cd ros2_ws + git clone https://github.com/husarion/rosbot_ros src/rosbot_ros + ``` -### `rosbot_controller` +### 🤖 Hardware -ROS2 hardware controllers configuration for ROSbots. - -## ROS API - -Available in [ROS_API.md](./ROS_API.md) - -## Usage on hardware - -To run the software on real ROSbot 2R, 2 PRO, also communication with the CORE2 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_ros2_firmware repository](https://github.com/husarion/rosbot_ros2_firmware). - -## Source build - -### Prerequisites - -Install all necessary tools: - -```bash -sudo apt-get update -sudo apt-get install -y python3-pip ros-dev-tools stm32flash -``` - -Create workspace folder and clone `rosbot_ros` repository: - -```bash -mkdir -p ros2_ws -cd ros2_ws -git clone https://github.com/husarion/rosbot_ros src/rosbot_ros -``` - -### Build and run on hardware - -Building: +#### Building ```bash export HUSARION_ROS_BUILD_TYPE=hardware @@ -72,25 +46,30 @@ rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y colcon build --symlink-install --packages-up-to rosbot --cmake-args -DCMAKE_BUILD_TYPE=Release ``` -Flash firmware: +#### Run the Robot -```bash -sudo su -source install/setup.bash -ros2 run rosbot_utils flash_firmware -exit -``` +1. Flash the firmware: -Running: + ```bash + sudo su + source install/setup.bash + ros2 run rosbot_utils flash_firmware + exit + ``` -```bash -source install/setup.bash -ros2 launch rosbot_bringup combined.launch.py -``` +> [!NOTE] +> To run the software on real ROSbots, communication with the CORE2 is required. Ensure the firmware is updated before running the micro-ROS agent. For detailed instructions, refer to the rosbot_ros2_firmware repository. + +2. Launch the robot: + + ```bash + source install/setup.bash + ros2 launch rosbot_bringup bringup.launch.py + ``` -### Build and run Gazebo simulation +### đŸ–Ĩī¸ Simulation -Building: +#### Building ```bash export HUSARION_ROS_BUILD_TYPE=simulation @@ -109,76 +88,18 @@ rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y colcon build --symlink-install --packages-up-to rosbot --cmake-args -DCMAKE_BUILD_TYPE=Release ``` -Running: +#### Run the Simulation ```bash source install/setup.bash ros2 launch rosbot_gazebo simulation.launch.py ``` -## Developer info - -### 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 tests -pre-commit run -a -``` - -After initialization [pre-commit configuration](.pre-commit-config.yaml) will applied on every commit. - -### Industrial CI - -```bash -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: - -``` bash -colcon test-result --verbose -``` - -### Format python code with [Black](https://github.com/psf/black) - -```bash -cd src/rosbot_ros -black rosbot* -``` - -### Testing `.github/workflows/industrial_ci.yaml` Locally - -At fist install [act](https://github.com/nektos/act): - -```bash -cd / -curl -s https://raw.githubusercontent.com/nektos/act/master/install.sh | sudo bash -``` - -And test the workflow with: - -```bash -act -W .github/workflows/industrial_ci.yaml -``` +## 🕹ī¸ Demo -## Demo +Explore demos showcasing the capabilities of ROSbots: -Below you can find demos with ROSbots: -| link | description | -| - | - | -| [rosbot-docker](https://github.com/husarion/rosbot-docker/tree/ros2) | Simple example how to drive ROSbot with `teleop_twist_keyboard` using docker | -| [rosbot-sensors](https://github.com/husarion/rosbot-sensors) | Visualize all ROSbot sensors | -| [rosbot-gamepad](https://github.com/husarion/rosbot-gamepad) | Stream a live video from Orbbec Astra to a window on your PC. Control the robot using `teleop-twist-keyboard` | -| [rosbot-telepresence](https://github.com/husarion/rosbot-telepresence) | Stream a live video from Orbbec Astra to a window on your PC. Control the robot using `teleop-twist-keyboard` | -| [rosbot-autonomy](https://github.com/husarion/rosbot-autonomy) | A combination of `mapping` and `navigation` projects allowing simultaneous mapping and navigation in unknown environments. | +| 📎 Link | 📖 Description | +| ---------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------ | +| [rosbot-telepresence](https://github.com/husarion/rosbot-telepresence) | Stream live video from Orbbec Astra to a PC and control the robot using `teleop-twist-keyboard` | +| [rosbot-autonomy](https://github.com/husarion/rosbot-autonomy) | Enables simultaneous mapping and navigation, allowing the robot to move in unknown environments. | diff --git a/ROS_API.md b/ROS_API.md index c92327a6..ae4480a0 100644 --- a/ROS_API.md +++ b/ROS_API.md @@ -1,46 +1,166 @@ -Use `bringup.launch.py` from `rosbot_bringup` to start all base functionalities for ROSbot 2, 2 PRO, 2R. It consists of following parts: +# ROSbot - Software -- `ekf_node` from `robot_localization`, it is used to fuse wheel odometry and IMU data. Parameters are defined in `ekf.yaml` in `rosbot_bringup/config`. It subscribes to `/rosbot_base_controller/odom` and `/imu_broadcaster/imu` published by ros2 controllers and publishes fused odometry on `/odometry/filtered` topic +Detailed information about content of rosbot package for ROS2. - **Subscribes** - - `/rosbot_base_controller/odom` (_nav_msgs/Odometry_) - - `/imu_broadcaster/imu` (_sensor_msgs/Imu_) +## Package Description - **Publishes** - - `/tf` (_tf2_msgs/TFMessage_) - `base_link`->`odom` transform - - `/odometry/filtered` (_nav_msgs/Odometry_) +### `rosbot` -Use `controller.launch.py` from `rosbot_controller`, it loads robot model defined in `rosbot_description` as well as ros2 control [rosbot_hardware_interfaces](https://github.com/husarion/rosbot_hardware_interfaces). It also starts controllers: +Metapackage that contains dependencies to other repositories. It is also used to define whether simulation dependencies should be used. -- `joint_state_broadcaster` -- `rosbot_base_controller` -- `imu_broadcaster` +### `rosbot_bringup` - **Subscribes** - - `/cmd_vel` (_geometry_msgs/Twist_) - - `/_motors_responses` (_sensor_msgs/JointState_) - - `/_imu/data_raw` (_sensor_msgs/Imu_) +Package that contains launch, which starts all base functionalities with the microros agent. Also configs for `robot_localization` and `laser_filters` are defined there. - **Publishes** - - `/tf` (_tf2_msgs/TFMessage_) - - `/tf_static` (_tf2_msgs/TFMessage_) - - `/_motors_cmd` (_std_msgs/Float32MultiArray_) - - `/rosbot_base_controller/odom` (_nav_msgs/Odometry_) - - `/imu_broadcaster/imu` (_sensor_msgs/Imu_) +**Available Launch Files:** -Use `simulation.launch.py` from `rosbot_gazebo` to start all base functionalities for ROSbot 2, 2 PRO, 2R in the Gazebo simulator. -If you want to spawn multiple robots use `simulation.launch.py` with the `robots` argument e. g.: +- `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. -```bash -ros2 launch rosbot_gazebo simulation.launch.py robots:='robot1={x: 0.0, y: -1.0}; robot2={x: 1.0, y: -1.0}; robot3={x: 2.0, y: -1.0}' -``` +**Launch Params:** -If you want to use your own world add to the world's sdf file gazebo sensors plugins inside any `` tag: +| 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 | **""** | -```xml - - -``` +> \*You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_bringup bringup.launch.py -s`). -> **Warning** -> The distance sensors' topics types from Gazebo simulation mismatch with the real ones. The range sensors are not implemented yet in the Gazebo Ignition (for more information look [here](https://github.com/gazebosim/gz-sensors/issues/19)). The real type is [sensor_msgs/msg/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) but simulated [sensor_msgs/msg/LaserScan](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/LaserScan.msg). The first value of the `ranges` in [sensor_msgs/msg/LaserScan](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/LaserScan.msg) is the `range` field of [sensor_msgs/msg/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg). +### `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](https://github.com/husarion/rosbot_hardware_interfaces). + +### `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 models: + +| MODEL | DESCRIPTION | +| ------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `rosbot` | Final configuration of rosbot with ability to attach external hardware. | +| `rosbot_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_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_utils` + +This package contains the stable firmware version with the flash script. + +### `rosbot_navigation` + +Package that contains navigation configurations and launch files for ROSbot. It integrates with `nav2` for autonomous navigation. + +**Available Launch Files:** + +- `navigation.launch.py` - launches the navigation stack with predefined parameters. + +**Launch Params:** + +| PARAMETER | DESCRIPTION | VALUE | +| ------------------------ | ----------------------------------------------------------------- | ---------- | +| **map** | Path to the map file used for navigation | **""** | +| **use_sim_time** | Whether to use simulation time | **False** | +| **params_file** | Path to the parameters file for navigation stack | **""** | + +> You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_navigation navigation.launch.py -s`). + +## 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_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_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_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_base_controller/odom`** | provides odometry data from the base controller of the ROSbot.
_[nav_msgs/Odometry][]_ | +| **`~/rosbot_base_controller/transition_event`** | indicates transition events in the lifecycle of the ROSbot 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_description/package.xml b/rosbot_description/package.xml index 9c9d5ad6..eb9c1995 100644 --- a/rosbot_description/package.xml +++ b/rosbot_description/package.xml @@ -13,8 +13,8 @@ https://github.com/husarion/rosbot_ros https://github.com/husarion/rosbot_ros/issues - Maciej Stepien Jakub Delicat + Maciej Stepien ament_cmake diff --git a/rosbot_gazebo/package.xml b/rosbot_gazebo/package.xml index 04c4e8b2..5fa4a0c9 100644 --- a/rosbot_gazebo/package.xml +++ b/rosbot_gazebo/package.xml @@ -13,8 +13,8 @@ https://github.com/husarion/rosbot_ros https://github.com/husarion/rosbot_ros/issues - Krzysztof Wojciechowski Jakub Delicat + Krzysztof Wojciechowski Rafal Gorecki husarion_gz_worlds