-
Notifications
You must be signed in to change notification settings - Fork 524
diff_drive_controller
The diff_drive_controller
package for a differential drive mobile base. See also the corresponding controller's ROS wiki page and the C++ API documentation.
The controller works with a velocity twist (subscribes to cmd_vel
of type geometry_msgs/Twist) from which it extracts the x
component of the linear
velocity and the z
component of the angular
velocity. Velocities on other components are ignored.
The data of the received velocity twist message is split and then sent on the two wheels of a differential drive wheel base using the hardware_interface::JointHandle::setCommand
method of the hardware_interface::VelocityJointInterface
. Odometry is computed from the feedback from the hardware (also via hardware_interface::VelocityJointInterface
using pointers and not relying on ROS interfaces (e.g. topics, services, actions)), and published over the odom
topic of type nav_msgs/Odometry.
Note that hardware_interface::VelocityJointInterface
inherits from hardware_interface::JointCommandInterface
which allows both reading joint state and commanding [effort|velocity|position]-based joints (see this answer).
Joints that are read-only should use hardware_interface::JointStateInterface
(not used by diff_drive_controller
) such as caster wheel joints that provide feedback from attached sensors.
As with all controllers of ROS control, a description of the robot is required as urdf/xacro.
Refer to this gazebo tutorial. Although this tutorial is helpful you should be aware that it was written for gazebo version 1.9 and some parts are not up to date.
Requires you to write your own robot class inheriting from hardware_interface::RobotHW
and implement the read()
and write()
methods. For an example see ros_control_boilerplate.
The sensors would be the encoders and the actuators would (most likely) be velocity controlled motors.
There are generally two 'types' (no official distinctions, merely suggestions) of hardware_interface
implementations (see this answer):
- those that use ROS msgs to communicate with nodes that implement the actual interface to the hardware
- those that do not use ROS msgs, but some other means (direct register access, a UDP/TCP connection, etc)