DiffBot Messages Package
As mentioned before, the nodes in ROS communicate with each other by publishing messages to topics.
ROS provides the std_msgs
package that includes ROS' common message types to represent primitive data types (see the ROS msg specification for primitive types) and other basic message constructs, such as multiarrays.
Note howerver, the following from the std_msgs
documentation:
Quote
The types in std_msgs
do not convey semantic meaning about their contents: every message simply has a field called "data".
Therefore, while the messages in this package can be useful for quick prototyping, they are NOT intended for "long-term" usage.
For ease of documentation and collaboration, we recommend that existing messages be used, or new messages created, that provide meaningful field name(s).
Diffbot Messages
Therefore, we create a package that contains message definitions specific to DiffBot.
The following command uses catkin-tools
to create the diffbot_msgs
package:
1 2 3 4 5 6 |
|
Note
The following is based on ROS Tutorials Creating Msg And Srv.
In this tutorial you can find the required configurations for the package.xml
and CMakeLists.txt
.
Encoders
Currently there is no encoder message definition in ROS (see the sensor_msgs
package)
which is why a dedicated message is created for the encoders. For this, a simple msg description file,
named Encoders.msg
is created in the msg/
subdirectory of this diffbot_msgs
package:
1 2 3 4 5 6 7 8 |
|
The message includes the message type Header
(see also Header msg) which includes common metadata fileds such as timestamp that is automatically
set by ROS client libraries.
Having this encoder message description gives semantic meaning to the encoder messages and for example avoids having two separate int32 publishers for each encoder. Combining the encoder message into a single one alleviates additional timing problems.
There exists also the common_msgs
meta package for common, generic robot-specific message types.
From the common_msgs
DiffBot uses for example the nav_msgs
for navigation with the navigation stack. Other relevant message definitions are the sensor_msgs/Imu
and sensor_msgs/LaserScan
,
where both are definitions from the sensor_msgs
package.
Wheel Commands
To command a joint velocity for each wheel diffbot_msgs
provides the WheelCmd.msg
.
This specifies the Header
and a float64 array for the angular wheel joint velocities.
1 2 3 4 5 6 |
|
Using rosmsg
After building the package and its messages using catkin build
let's make sure that ROS can see it using the rosmsg show command.
1 2 3 4 5 6 |
|
Tip
When using the a ros command such as rosmsg
make use of the Tab key to auto complete the message name.
ROSSerial
The generated messages in this packages are used on the Teensy microcontroller, which is using rosserial
.
Integrating these messages requires the following steps.
- Generate rosserial libraries in a temporary folder using the
make_libraries
script:
1 |
|
This will generate all messages for ALL installed packages, but in our case only the diffbot_msgs
package is needed to avoid missing includes.
- Copy the generated
~/Arduino/tmp/diffbot_msgs
message folder to thesrc
folder of therosserial
Arduino library. Whenrosserial
was installed with the Arduino Library Manager, the location is~/Arduino/libraries/Rosserial_Arduino_Library/
.
Usage
The new messages, specific to DiffBot, can be used by including the generated header, for example #include <diffbot_msgs/Encoders.h>
.
References
- Tutorials Arduino IDE Setup, specifically Install ros_lib into the Arduino Environment
rosserial
limitations:float64
is not supported on Arduino.