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)
You can use conda (experimental), or docker. For the first method, follow this readme. Otherwise, look here.
- clone the repo
git clone --recurse-submodules https://github.com/giulioturrisi/Differential-Drive-Robot.git
-
install miniforge (x86_64)
-
create an environment using the file in the folder installation/conda:
conda env create -f mamba_environment.yml
- follow the instruction here to install ros-humble, and press
mamba install ros-humble-slam-toolbox
-
download CoppeliaSim
-
add in your .bashrc
alias ddrive_env="conda activate ddrive_env && source your_path_to/Differential-Drive-Robot/ros2_ws/install/setup.bash"
export COPPELIASIM_ROOT_DIR=your_path_to/CoppeliaSim
- add the following ls in ros2_ws/src/simROS2/meta/interfaces.txt
geometry_msgs/msg/Twist
geometry_msgs/msg/TwistStamped
sensor_msgs/msg/LaserScan
- start your environment and go in ros2_ws
ddrive_env
cd your_path_to/Differential-Drive-Robot/ros2_ws
rosdep install -y -r -q --from-paths src --ignore-src --rosdistro humble
ulimit -s unlimited
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release
- if you need acados, go inside the acados/acados folder and press
mkdir build
cd build
cmake -DACADOS_WITH_QPOASES=ON -DACADOS_WITH_OSQP=ON ..
make install -j4
pip install -e ./../interfaces/acados_template
then in your .bashrc, add
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:"/your_path_to/Differential-Drive-Robot/python_scripts/controllers/acados/lib"
export ACADOS_SOURCE_DIR="/your_path_to/Differential-Drive-Robot/python_scripts/controllers/acados"
All the commands below can be more easily launched via some aliases, such as
alias ddrive_launch_rviz="ros2 run rviz2 rviz2 -d your_path_to/Differential-Drive-Robot/ros2_ws/src/utilities/rviz_config/common.rviz"
alias ddrive_launch_slam="ros2 launch slam_toolbox online_async_launch.py"
alias ddrive_launch_planners="ros2 run planners run_planners"
alias ddrive_launch_joy="ros2 launch teleop_twist_joy teleop-launch.py joy_config:='xbox'"
alias ddrive_launch_controllers="ros2 run controllers run_controllers"
alias ddrive_launch_lidar_odometry="ros2 launch pointcloud_to_laserscan sample_laserscan_to_pointcloud_launch.py | ros2 launch kiss_icp odometry.launch.py topic:=/pointcloud visualize:=false child_frame:=base_footprint max_range:=5.0 min_range:=0.2"
alias ddrive_launch_state_publisher="ros2 launch state_estimation state_publisher_launch.py "
alias ddrive_launch_sim_dynamics="cd $COPPELIASIM_ROOT_DIR && ./coppeliaSim.sh -f /your_path_to/Differential-Drive-Robot/coppeliasim_simulation/dynamics.ttt"
alias ddrive_launch_sim_kinematics="cd $COPPELIASIM_ROOT_DIR && ./coppeliaSim.sh -f your_path_to/Differential-Drive-Robot/coppeliasim_simulation/kinematics.ttt"
Follow the commands below to run all the framework:
- on a new terminal first launch the simulation
ddrive_launch_sim_kinematics (scene with kinematics)
ddrive_launch_sim_dynamics (scene with dynamics)
- on each new terminal, then launch all the other packages
ddrive_launch_joy (to use the joystick)
ddrive_launch_rviz (visualization)
ddrive_launch_planners (planning)
ddrive_launch_controllers (control)
ddrive_launch_lidar_odometry (tf and kiss-icp)
ddrive_launch_slam (slam-toolbox)
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!