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).
Therefore, we create a package that contains message definitions specific to DiffBot.
The following command uses catkin-tools
to create the diffbot_msgs
package:
ros_ws/src$ catkin create pkg diffbot_msgs --catkin-deps message_generation std_msgs
Creating package "diffbot_msgs" in "/home/fjp/git/ros_ws/src"...
WARNING: Packages with messages or services should depend on both message_generation and message_runtime
Created file diffbot_msgs/package.xml
Created file diffbot_msgs/CMakeLists.txt
Successfully created package files in /home/fjp/git/ros_ws/src/diffbot_msgs.
!!! 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
.
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
]({{ diffbot_repo_url }}/diffbot_msgs/msg/Encoders.msg) is created in the msg/
subdirectory of this diffbot_msgs
package:
# This is a message to hold number of ticks from Encoders
Header header
# Use an array of size two of type int32 for the two encoders.
# int32 is used instead of int64 because it is not supporte by Arduino/Teensy.
# An overflow is also unlikely with the encoders of the DG01D-E
# motor with its encoder because of its low encoder resolution
int32[2] ticks
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.
To command a joint velocity for each wheel diffbot_msgs
provides the [WheelCmd.msg
]({{ diffbot_repo_url }}/diffbot_msgs/msg/WheelCmd.msg).
This specifies the Header
and a float64 array for the angular wheel joint velocities.
# This is a message that holds commanded angular joint velocity
Header header
# Use an array of type float32 for the two wheel joint velocities.
# float32 is used instead of float64 because it is not supporte by Arduino/Teensy.
float32[] velocities
After building the package and its messages using catkin build
let's make sure that ROS can see it using the rosmsg show command.
$ rosmsg show diffbot_msgs/Encoders
std_msgs/Header header
uint32 seq
time stamp
string frame_id
int32[2] encoders
!!! tip
When using the a ros command such as rosmsg
make use of the ++tab++ key to auto complete the message name.
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:
rosrun rosserial_client make_libraries ~/Arduino/tmp/
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/
.
The new messages, specific to DiffBot, can be used by including the generated header, for example #include <diffbot_msgs/Encoders.h>
.
- Tutorials Arduino IDE Setup, specifically Install ros_lib into the Arduino Environment
rosserial
limitations:float64
is not supported on Arduino.