This is a modified version of clearpath_simulator Version 0.34 from Clearpath Robotics that uses Gazebo 8 (Harmonic) as its primary simulator. Installation, how to use guide and some helpful resources are given below.
version01.mp4
✋ If you plan on using a Xbox One/Xbox 360 controller, check How to install and use Xbox One Controller
under the Useful Resources section.
✋ All tutorials in thie repository assumes you can send TwistStamped commands either through a controller or from keyboard or using rqt_joystick
.
❗ Please note all the original packages from clearpath_simulator v0.3 have been modified for ROS 2 Jazzy and Gazebo Harmonic compatiblity. Hence, only my forks of those packages is known to work at this time.
- ✅ Ubuntu 22.04 (via source build) and Ubuntu 24.04 (via debian packages)
- ✅ Compatible with Gazebo Harmonic and ROS 2 Jazzy
- ✅ Xbox One S controller support
- ✅ Automatic conversion between Twist and TwistStamped messages
- ✅ Custom names for
robot.yaml
configuration scripts. - ✅ Asus Xtion simulated RGB-D camera
- ✅ Intel Realsense simulated RGB-D camera
- ❌ PointCloud from RGBD cameras
- ✅ A200 Husky
This simulator depends on the following packages
- Gazebo Harmonic
- Moveit2 (Jazzy version)
- Nav2 (Jazzy version)
- Packages defined in
clearpath_sim.repos
- Nice to haves
- :white_large_square Add
Contributions.md
- ✅ RGB-D sensor support.
- :white_large_square Rviz visualization
- :white_large_square Add the
outdoor.sdf
world
- :white_large_square Add support for multi-robot simulation
- ⬜ 2D LiDAR Sensor
- ⬜ 3D LiDAR Sensor
- ⬜ SLAM example to save a map
- ⬜ Nav2 MPPI controller example
- ⬜ Multi-robot example
cpr_gazebo
contains a number of custom repository worlds from Clearpath Robotics but modifying them to be compatible with Harmonic will take some time and effort. If you are interested to helping out with modifying these works and contributing to this project in general, please don't hestiate to reaching out to me.
-
Install ROS 2 Jazzy desktop: https://docs.ros.org/en/jazzy/Installation/Ubuntu-Install-Debs.html
-
Build this workspace
cd ~
git clone https://github.com/Mechazo11/clearpath_simulator_harmonic
mkdir ~/clearpath_simulator_harmonic_ws/
cd ~/clearpath_simulator_harmonic/
vcs import src < clearpath_sim.repos --recursive
rosdep install -r --from-paths src --rosdistro jazzy -i -y
sudo apt install ros-jazzy-rmw-cyclonedds-cpp
source /opt/ros/jazzy/setup.bash
colcon build --symlink-install --cmake-args -DCMAKE_CXX_FLAGS="-w"
Click to expand
- If you are using Ubuntu 22.04, and had previously used ROS 2 Humble, you need to first ensure that the ROS 2 Humble global workspace is not sourced. The first step is to just comment out ```source /opt/ros/humble/setup.bash``` from ```.bashrc``` file.- [Optional] step: Remove
/opt/ros/humble
from globalPATH
variable.
echo $PATH # check /opt/ros/humble is included in the PATH variable
export PATH=$(echo $PATH | tr ':' '\n' | grep -v "/opt/ros/humble" | tr '\n' ':' | sed 's/:$//')
- WARNING!! in the event the above doesn't work, the easiest thing to do is to remove ROS 2 Humble binaries from system-level using
sudo apt remove ros-humble*
. Please note, if you need to use ROS 2 Humble again, you would need to reinstall the binaries or build ROS 2 humble from source.
sudo apt update
sudo apt upgrade
sudo apt-get install python3-dev python3-tk libyaml-cpp-dev joystick
pip3 install numpy catkin_pkg empy lark jinja2 typeguard pyyaml
Build and install the following workspaces in sequence. Will take about ~1 hour and ~35-40 GB disk space
-
Build a ROS 2 Jazzy workspace: https://github.com/Mechazo11/ubuntu22_jazzy_ws
-
Build Gazebo Harmonic workspace: https://github.com/Mechazo11/gazebo_harmonic_ws
-
Build Moveit2, Nav2 (Jazzy compatible) workspace: https://github.com/Mechazo11/moveit2_jazzy_ws
-
Build this workspace using the following steps
cd ~
git clone https://github.com/Mechazo11/clearpath_simulator_harmonic.git
cd clearpath_simulator_harmonic/
vcs import src < clearpath_sim.repos --recursive
rosdep install -r --from-paths src --rosdistro jazzy -i -y
source ~/ubuntu22_jazzy_ws/install/setup.bash
source ~/gazebo_harmonic_ws/install/setup.bash
source ~/moveit2_nav2_jazzy_ws/install/setup.bash
colcon build --symlink-install --cmake-args -DCMAKE_CXX_FLAGS="-w"
source ~/ubuntu22_jazzy_ws/install/setup.bash
source ~/gazebo_harmonic_ws/install/setup.bash
source ~/moveit2_nav2_jazzy_ws/install/setup.bash
source ~/clearpath_simulator_harmonic/install/setup.bash
source /opt/ros/jazzy/setup.bash
source ~/clearpath_simulator_harmonic/install/setup.bash
sudo ln -s /dev/input/js2 /dev/input/xbox
sudo udevadm control --reload-rules
sudo udevadm trigger
ls -l /dev/input/xbox
ros2 launch clearpath_gz empty_launch.py robot_config_yaml:=husky_a200_sample.yaml
- Test robot's movement with a TwistStamped message
ros2 topic pub /a200_0000/platform_velocity_controller/cmd_vel geometry_msgs/msg/TwistStamped "{header: {stamp: {sec: 0, nanosec: 0}, frame_id: 'base_link'}, twist: {linear: {x: 1.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.5}}}"
-
If the robot moves, then all controller configurations have been setup correctly, now we can use a gamepad to control the robot
-
Launch the
warehouse_cpr
world that brings in a A200 Husky robot
ros2 launch clearpath_gz simulation.launch.py robot_config_yaml:=husky_a200_sample.yaml world:=warehouse_cpr
- Teleop with gamepad
- Press and Hold
LB
to enable teleop - Press and Hold
RB
to enable faster movement - Analog stick 1 controls both linear and angular velocities
- Press and Hold
Click to expand
- Clearpath uses a single yaml file to define its robots. More details here https://docs. clearpathrobotics.com/docs/ros/config/yaml/overview/.
- Simulate
- Migration from Gazebo Classic: SDF
- ROS 2 and Gazebo Integration Best Practices
- Spherical Coordinates
- Finding resources
- GZ_SIM_RESOURCE_PATH
- ros2_control_demos
- Simulation of a 4WS Robot Using ROS2 Control and Gazebo: This example moved a 4W drive robot using ros2_control
- teleop_twist_joy: https://github.com/ros2/teleop_twist_joy
- Teleo with a joystick: https://articulatedrobotics.xyz/tutorials/mobile-robot/applications/teleop/
- teleop_twist_joy: https://github.com/ros2/teleop_twist_joy
- On using Substitutions in ROS 2 launch files: https://daobook.github.io/ros2-docs/xin/Tutorials/Launch-Files/Using-Substitutions.html
- Pose publisher demo: https://github.com/gazebosim/gz-sim/blob/gz-sim8/examples/worlds/pose_publisher.sdf
- Documentations on using gazebo_ros2_control: https://control.ros.org/rolling/doc/gazebo_ros2_control/doc/index.html
- ROS 2 Gazebo tutorial robot simulation with
ros2_control
: https://www.youtube.com/watch?v=PM_1Nb9u-N0 - An excellent example for correctly defining
ros2_control
plugin names to connect with Gazebo Harmonic: https://www.youtube.com/watch?v=u54WAlAewMU - Convert Twist to TwistStamped message: https://github.com/joshnewans/twist_stamper
- Complete list of Github markdown emoji support: https://gist.github.com/rxaviers/7360908
-
To find out where
ros2_control
,gazebo
plugins andros_gz_bridge
elements of A200 Husky robots are defined, start looking intoclearpath_common/clearpath_platform_description/urdf/a200
. The same is true for the other supported robots -
clearpath_generator_common.generator.py.DescriptionGenerator
is responsible for writing therobot.urdf.xacro
which is later on read by therobot_spwan.launch.py
file inclearpath_gz
package.
-
Ensure
dkms
,bluez
andxpadneo
drivers are installed. Bu defaultdkms
andlinux headers
will be installed in Ubuntu 22.04. Installbluez
:sudo apt-get install bluez
-
Install
xpadneo
cd ~Downloads/
git clone https://github.com/atar-axis/xpadneo.git
cd ~xpandneo/
sudo ./install.sh
- Pair a Xbox controller, follow the steps shown below
- Clone
joy_tester
library and build it
cd ~/clearpath_simulator_harmonic_ws/src
git clone https://github.com/joshnewans/joy_tester.git
cd ..
colcon build --symlink-install --packages-select joy_tester
source ./install/setup.bash
-
Then launch the
joy_tester
package to test if all the buttons are working properly. -
In one terminal, run the teleop_twist_joy
ros2 launch teleop_twist_joy teleop-launch.py joy_config:='xbox'
- In the other terminal run the
test_joy
source ~/clearpath_simulator_harmonic_ws/install/setup.bash
ros2 run joy_tester test_joy
- If successfull you should see something like the following
- Now identify which
jsx
represents the connected gamepad. First find out how manyjsx
device nodes are there
ls /dev/input/js*
- Test each node until you find the one that reacts with a button press. In my case it was
js2
node
jstest /dev/input/js2
-
Now create a symbolic link between this node and
/dev/input/xbox
and create udev rule- Create symbolic links and
udev
rule:sudo ln -s /dev/input/js2 /dev/input/xbox
- Identify unique properties:
udevadm info -a -n /dev/input/js2 | grep -E 'ATTRS{idVendor}|ATTRS{idProduct}|ATTRS{name}' ```. An **example** is shown below, DO NOT COPY THESE ```bash ATTRS{name}=="Xbox Wireless Controller" ATTRS{idProduct}=="0032" ATTRS{idVendor}=="8087" ATTRS{idProduct}=="0608" ATTRS{idVendor}=="05e3" ATTRS{idProduct}=="0002" ATTRS{idVendor}=="1d6b"
- Create udev rule file:
sudo nano /etc/udev/rules.d/99-xbox-controller.rules
and copy these attributes (after filling them out wiht idVendor and idProduct unique to your controller)
SUBSYSTEM=="input", KERNEL=="js[0-9]*", ATTRS{idVendor}=="05e3", ATTRS{idProduct}=="0002", SYMLINK+="input/xbox"
Make sure to change with actual values
- Reload Udev rules and trigger
sudo udevadm control --reload-rules sudo udevadm trigger
- Verify simlink:
ls -l /dev/input/xbox
you should see something like this
- Create symbolic links and
[spawner-15] [WARN] [1734830398.851778889] [a200_0000.spawner_platform_velocity_controller]: Controller already loaded, skipping load_controller
[spawner-15] [ERROR] [1734830398.854877834] [a200_0000.spawner_platform_velocity_controller]: Failed to configure controller
[spawner-14] [WARN] [1734830398.862552805] [a200_0000.spawner_joint_state_broadcaster]: Controller already loaded, skipping load_controller
[spawner-14] [ERROR] [1734830398.865012741] [a200_0000.spawner_joint_state_broadcaster]: Failed to configure controller
Try the following commands
ps aux | grep gzserver
pgrep gzserver
tigerwi+ <#PID> 0.0 0.0 9708 2560 pts/1 S+ 19:17 0:00 grep --color=auto gzserver
kill -2 <#PID>
killall gzserver
killall -9 gzserver