Skip to content

ROS interface for EduArt's generic robot drive stack

License

Notifications You must be signed in to change notification settings

Bento-Robotics/edu_drive

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

33 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

edu_drive

This package comprises a ROS interface for EduArt's generic drive concept. It covers several kinematic concepts: Differential drive, Mecanum steering and Skid steering. All three can be used in dependency of the mounted wheels and the configuration of YAML parameters.

Launching the Robot

In order to run the robot, you need to launch the appropriate launch file. In the launch folder, there is a prepared template. Configure the correct kinematic concept and motor parameters. A description of the YAML file can be found below.

roslaunch edu_drive edu_drive.launch

When everthing is initialized well, one should see the following output:

# Listener start
CAN Interface: can0
[ INFO] [1651663592.994224328]: Instanciated robot with vMax: 0.366519 m/s and omegaMax: 0.733038 rad/s
...

After startup, the drive system is in the deactivated state.

Please notice also, that the ROS variables ROS_MASTER_URI and ROS_IP should be set properly. If you have a changing IP-address of the robot, you might consider to use the following bash code in your ~/.bashrc:

MYIP=`hostname -I | awk '{print $1}'`
export ROS_MASTER_URI=http://${MYIP}:11311
export ROS_IP=${MYIP}

YAML file parameters

tag description
canInterface SocketCAN interface, e.g. can0
frequencyScale Divider of PWM frequency, Base frequency: 500kHz (Divider=1)
inputWeight Low pass filtering, setpoint = inputWeight*setpoint_new + (1-inputWeight)*setpoint_old
maxPulseWidth Limitation of pulse width, meaningful values [0; 100]
timeout Dead time monitoring of communication (in milliseconds)
kp, ki, kd Controller coefficients
antiWindup Enable anti windup monitoring of closed-loop controller
invertEnc Invert encoder signal
responseMode Activate transmission of RPM or position measurements of motor controller
controllers Number of motor controllers used
canID Motorcontroller ID (set by DIP switch on motor controller PCB)
gearRatio Gear ratio of connected geared motors
encoderRatio Encoder pulses per motor revolution (rising and falling edge evaluation)
rpmMax Maximum revolutions per minute of geared motor pinion
channel Used channel of motor controller. There are single-channel motorshields and dual-channel motorshields. Meaningful values are 0 or 1.
kinematics Three-dimensional vector describing the conversion from Twist messages in motor revolutions. See explanation below.

Calculation of the kinematic parameters

The kinematic concept uses a conversion matrix for the conversion of twist parameters and wheel speeds.

, where ωi are the wheel's angular velocities and vx, vy and ω are Twist values. The matrix T can be calculated as follows:

for a four-wheeled robot. kxi, kyi and kωi are the translation parameters from one space to the other. These parameters include the wheel radius r as well as the robot length lx and robot width ly.

Example for a Differential drive

Example for a Mecanum drive

Setting up a Raspberry PI4 SBC from scratch

  1. Install Basis OS, Raspbian GNU/Linux 11 (bullseye) has been tested
  2. Update and install necessary packages
sudo apt update
sudo apt upgrade
sudo reboot
sudo apt install can-utils build-essential cmake git
  1. Add the following entries in /etc/rc.local
ip link set can0 up type can bitrate 500000
echo 16 > /sys/class/gpio/export
echo "out" > /sys/class/gpio/gpio16/direction

echo 22 > /sys/class/gpio/export
echo "out" > /sys/class/gpio/gpio22/direction
echo 1 > /sys/class/gpio/gpio22/value
  1. Install ROS
sudo apt install python3-empy libboost1.71-all-dev libtinyxml2-dev lz4 libroslz4-dev liblz4-dev libbz2-dev lbzip2 libgtest-dev libgpgme-dev libspnav-dev python3-rosdep python3-rosinstall-generator python3-vcstools ros-cmake-modules libpoco-dev 
rosdep update
mkdir ~/ros_catkin_ws
cd ros_catkin_ws
python -m rospkg.os_detect
rosdep install -ay --os=debian:bullseye
rosdep update
rosinstall_generator ros_comm geometry_msgs sensor_msgs joystick_drivers diagnostic_updater --rosdistro noetic --deps --tar > noetic-ros_comm.rosinstall
sudo ./src/catkin/bin/catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --install-space /opt/ros/noetic -j4
sudo reboot
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
catkin_init_workspace
git clone https://github.com/EduArt-Robotik/edu_drive.git
cd ..
catkin_make
source devel/setup.bash

Now, the launch file should be started. Please adjust the parameters in edu_drive.yaml before.

roslaunch launch/edu_drive.launch

About

ROS interface for EduArt's generic robot drive stack

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • C++ 87.6%
  • CMake 11.3%
  • Other 1.1%