ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

how to utilise diff_drive_controller package in my robot?

asked 2017-07-12 08:15:14 -0500

Dear all,

I need your help to fill some gaps in my head :) So I have built a moving robot based on differential driving. Since it is the most popular drive (because of its simplicity) I searched for available packages and I found diff_drive_controller.

As it is stated in the Overview section, "Control is in the form of a velocity command, that is split then sent on the two wheels of a differential drive wheel base."

So I expect that this controller is subscribed in topic that accepts cmd_vel messages as commands, which is true.

But then what about encoders? I was expecting to provide two topics such as lwheel and rwheel to get encoders' pulses output but it is not documented. Similarly, I was expecting to publish in 2 topics the velocities for the wheels (joints).

Yes, I have found the differential_drive package (which was discontinued since groovy) but I though to try diff_drive_controller first.

Regards, Angelos

I'm sure that I miss something and I ask kindly your help.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2017-07-12 09:06:24 -0500

gvdhoorn gravatar image

updated 2017-07-12 09:12:45 -0500

In order to be able to use the diff_drive_controller from ros_control, you'll have to write a hardware_interface that allows diff_drive_controller to communicate with your sensors and actuators. A hardware_interface is basically a C++ class that has read() and write() methods and is a specialisation of a generic hardware_interface and knows how to read sensors and write to actuators (or their intermediate registers / whatever) for your specific hardware platform.

It's an abstraction that allows the generic diff_drive_controller to use your specific hardware, without knowing anything about your hardware.

For a mobile base using a differential drive, the sensors would be the encoders and the actuators would (most likely) be velocity controlled motors.

There are generally two 'types' of hardware_interface implementations:

  1. those that use ROS msgs to communicate with nodes that implement the actual interface to the hardware
  2. those that do not use ROS msgs, but some other means (direct register access, a UDP/TCP connection, etc)

Personally I prefer type 2, but if you already have nodes that expose topics which carry and accept the data you need (such as your lwheel and rwheel and "2 topics the velocities for the wheels") then a type 1 is obviously a possibility.

See #q263501 for a recent related question.

edit flag offensive delete link more

Comments

1

Note that I completely made the type 1 and type 2 distinction up, that is not official terminology at all.

It does however reflect the types of implementations I've come across - and written myself.

gvdhoorn gravatar image gvdhoorn  ( 2017-07-12 09:08:25 -0500 )edit

Thanks gvdhoorn, so I see that I need to research on the implementation of this hardware interface. Yes, I feel that I'm closer to implementation 2 as I have already developed a communication that exchanges data with my controller board (arduino M0) which is not in ROS. Thanks!

angelos.p gravatar image angelos.p  ( 2017-07-12 09:13:02 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2017-07-12 08:15:14 -0500

Seen: 1,362 times

Last updated: Jul 12 '17