This package has been tested on ROS Melodic and Noetic, it contains ROS nodes to control motors powered by the ez-Wheel Safety Wheel Drive (SWD®) technology.
SWD® Core Safety gear motor |
SWD® 150 Safety wheel drive |
SWD® StarterKit Development kit for AGV and AMR |
This package has been tested on x64_86 and armhf machines. Pre-built packages are available for ROS Noetic on Ubuntu 20.04 (for x64_86 and armhf).
- Two SWD® based wheels
- Ubuntu 20.04
- ROS Noetic
swd-services (>= 0.1.0)
In order to install swd_ros_controllers
, you need to add the ez-Wheel repository to /etc/apt/sources.list
.
echo "deb http://packages.ez-wheel.com:8081/ubuntu focal main" | sudo tee -a /etc/apt/sources.list
Then download and add the GPG key using following command:
wget -qO - http://packages.ez-wheel.com:8081/archive.key | sudo apt-key add -
Now, you should be able to install the ros-noetic-swd-ros-controllers
package using apt
:
sudo apt update && sudo apt install ros-noetic-swd-ros-controllers
To compile the package, make sure you have added the ez-Wheel repository to your /etc/apt/sources.list
as specified above.
Then you need to install swd-services
using:
sudo apt-get update && sudo apt install swd-services
In the following instructions, replace <rosdistro>
with the name of your ROS distro (e.g., noetic
).
source /opt/ros/<rosdistro>/setup.bash
mkdir -p ~/ros_ws/src/
cd ~/ros_ws/src/
git clone https://github.com/ezWheelSAS/swd_ros_controllers.git
cd ..
catkin_make install
source ~/ros_ws/install/setup.bash
The package comes with a preconfigured .launch
file for the SWD® Starter Kit:
roslaunch swd_ros_controllers swd_diff_drive_controller.launch
Or you can run it with a custom configuration, the minimum required parameters are:
rosrun swd_ros_controllers swd_diff_drive_controller \
_left_swd_config_file:="/path/to/swd_left.ini" \
_right_swd_config_file:="/path/to/swd_right.ini" \
_baseline:=0.485
This controller drives two ez-Wheel SWD® wheels as a differential-drive robot.
left_swd_config_file
of typestring
: Path to the.ini
configuration file of the left motor (mandatory parameter).right_swd_config_file
of typestring
: Path to the.ini
configuration file of the right motor (mandatory parameter).baseline_m
of typedouble
: The distance (in meters) between the 2 wheels (mandatory parameter).pub_freq_hz
of typeint
: Frequency (in Hz) of published odometry and TFs (default50
).command_timeout_ms
of typeint
: The delay (in milliseconds) before stopping the wheels if no command is received (default1000
).base_frame
of typestring
: Frame ID for the moving platform, used in odometry and TFs (default'base_link'
) (see REP-150 for more info).odom_frame
of typestring
: Frame ID for theodom
fixed frame used in odometry and TFs (default'odom'
) (see REP-150 for more info).publish_odom
of typebool
: Publish odometry messages (defaulttrue
).publish_tf
of typebool
: Publish odometry TF (defaulttrue
).publish_safety_functions
of typebool
: Publishswd_ros_controllers::SafetyFunctions
message (defaulttrue
).wheel_max_speed_rpm
of typedouble
: Maximum allowed wheel speed (in RPM), if a target speed of one of the wheels is above this limit, the controller will limit the speed of the two wheels without changing the robot's trajectory (default75.0
).wheel_safety_limited_speed_rpm
of typedouble
: Wheel safety limited speed (SLS) (in RPM), if an SLS signal is detected (from a security LiDAR for example), the wheel will be limited internally to the configured SLS limit, the ROS controller uses this value to limit the target speed sent to the motor in the SLS case (default30.0
).have_backward_sls
of typebool
: Specifies if the robot have a backward SLS signal, coming for example from a back-facing security LiDAR. If an SLS signal is available for backward movements, set this totrue
to take it into account. Otherwise, set the parameter tofalse
, this will limit all backward movements to the selectedwheel_safety_limited_speed_rpm
(defaultfalse
).positive_polarity_wheel
of typestring
: Internal parameter, used to select which wheels is set to a positive polarity (default'Right'
).control_mode
of typestring
: This parameter selects the control mode of the robot, if'Twist'
is selected, the node will subscribe to the~cmd_vel
topic, if'LeftRightSpeeds'
is selected, the node subscribe to~set_speed
(default'Twist'
).left_encoder_relative_error
of typedouble
: Relative error for left wheel encoder, used to calculate variances and propagate them to calculate the uncertainties in the odometry message. Each encoder acquisitionDIFF_LEFT_ENCODER
is modeled as:DIFF_LEFT_ENCODER +/- abs(left_encoder_relative_error * DIFF_LEFT_ENCODER)
(default0.05
corresponding to 5% of error).right_encoder_relative_error
of typedouble
: Relative error for right wheel encoder, used to calculate variances and propagate them to calculate the uncertainties in the odometry message. Each encoder acquisitionDIFF_RIGHT_ENCODER
is modeled as:DIFF_RIGHT_ENCODER +/- abs(right_encoder_relative_error * DIFF_RIGHT_ENCODER)
(default0.05
corresponding to 5% of error).
~cmd_vel
of typegeometry_msgs::Twist
: Target linear and angular velocities (whencontrol_mode:='Twist'
, this is the default).~set_speed
of typegeometry_msgs::Point
: Target speeds in rad/s for left (Point.x
) and right (Point.y
) wheels (whencontrol_mode:='LeftRightSpeeds'
).~soft_brake
of typestd_msgs::Bool
: Activate or release the soft brake, sendfalse
to release the brake, ortrue
to activate it.
~odom
of typenav_msgs::Odometry
: Odometry message based on wheels encoders, containing the pose and velocity of the robot with their's associated uncertainties. Unless disabled by thepublish_tf
parameter, TFs with the same information are also published.~safety
of typeswd_ros_controllers::SafetyFunctions
: Safety messages communicated by the wheels via CANOpen, the message includes information about Safe Torque Off (STO), Safety Limited Speed (SLS), Safe Direction Indication (forward/backward) (SDI+/-), and Safe Brake Control (SBC).
This message encodes the safety functions read from the SWD via CANOpen.
Header header
bool safe_torque_off
bool safe_brake_control
bool safety_limited_speed
bool safe_direction_indication_forward
bool safe_direction_indication_backward
For any questions, please open a GitHub issue.
ez-Wheel® is an innovative company founded in 2009 and located in Angoulême, France. The ez-Wheel company has developed the first industrial drive wheel, integrating electric traction motor, embedded electronics and rechargeable batteries.
This revolutionary solution, which quickly turns any manually handled platform into an electrically assisted one. Our solutions have been adopted by hundreds of end-users to improve productivity and prevent work accidents caused by manual handling. Our products are used in a variety of applications, in fields of Automotive, Factory logistics, Warehouses, Food processing, Hospitals and Pharmaceutical industries.
The new SWD® product family targets industrial robotics applications, like Autonomous Mobile Robots (AMRs) and Automatic Guided Vehicles (AGVs). It provides a unique solution for safety critical systems, which provides safety features according to the ISO 3691-4 standard.
The ez-Wheel® company has developed a unique know-how in embedded electronics, including safety critical systems, applied to battery powered electric traction.