This repo contains the code for controlling both a real and a simulated differential drive robot via ROS2 using different planners, controllers, and open-source libraries for slam and odometry.
- Approximate linearization
- Input-Output linearization
- Input-Output linearization + Linear MPC via Casadi
- Dynamic linearization
- Nonlinear Lyapunov
- Nonlinear MPC via Casadi
- Nonlinear MPC via Acados
- Iterative Linear Quadratic Regulator
- Iterative Linear Quadratic Regulator via Crocoddyl
- Predictive Sampling MPC
- A*
- Breadth First search
- Djikstra
- Greedy Best First search
- RRT
- RRT* (in progress)
- RRT-primitives
It includes the following folders and subfolders:
-
python_scripts
: most of the ROS2 nodes call some classes here -
coppeliasim_simulation
: scenes used for simulating the robot (dynamically enabled or not) -
ros2_ws
: collection of ROS2 nodes for controlling the robot with the aid of some external tools such asslam_toolbox
(generate a map and localization) andkiss-icp
(lidar odometry)
- clone the repo
git clone --recurse-submodules https://github.com/giulioturrisi/differential_drive.git
-
extract CoppeliaSim in Differential-Drive-Robot/coppeliasim_simulation
-
add the following ls in ros2_ws/src/simExtROS2/meta/interfaces.txt
geometry_msgs/msg/Twist
geometry_msgs/msg/TwistStamped
sensor_msgs/msg/LaserScan
- build the docker file inside Differential-Drive-Robot/docker_file/integrated_gpu or /nvidia
docker build -t ros2_humble .
- add alias to start the docker
cd
gedit .bashrc
alias ddrive_humble='xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix:rw --device=/dev/input/ -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY -e QT_X11_NO_MITSHM=1 --gpus all --name ddrive_humble ros2_humble' (if used /nvidia)
alias ddrive_humble="xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix --device=/dev/dri --device=/dev/input/ -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY --name ddrive_humble ros2_humble" (if used /integrated_gpu)
alias ddrive_humble='xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix -v /mnt/wslg:/mnt/wslg -v /usr/lib/wsl:/usr/lib/wsl --device=/dev/dxg -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY -e XDG_RUNTIME_DIR=$XDG_RUNTIME_DIR -e PULSE_SERVER=$PULSE_SERVER -e LD_LIBRARY_PATH=/usr/lib/wsl/lib --name ddrive_humble ros2_humble' (if Windows Linux Subsystem)
alias ddrive='docker exec -it ddrive_humble bash' (to attach a new terminal to the running docker)
- start docker and build
ddrive_humble
cd ros2_ws
rosdep install -y -r -q --from-paths src --ignore-src --rosdistro humble
ulimit -s unlimited
colcon build --symlink-install
All the commands below can be easily launched via some aliases. Check them by activating the docker ddrive_humble
and writing on the keyboard launch_
(plus tab for the autocomplete)
Follow the commands below to run all the framework:
- on a new terminal first launch the simulation
launch_sim_kinematics (scene with kinematics)
launch_sim_dynamics (scene with dynamics)
- on each new terminal, then launch all the other packages
launch_joy (to use the joystick)
launch_rviz (visualization)
launch_planners (planning)
launch_controllers (control)
launch_lidar_odometry (tf and kiss-icp)
launch_slam (slam-toolbox)
launch_state_publisher (filter for encoder and lidar)
ros2 launch ydlidar_ros2_driver ydlidar_launch.py (ydlidar - only real robot)
- you can choose a goal pose in Rviz2 clicking 2D Goal Pose
Still working in progress, the real robot exists but it's not yet finalized!