Contents
FORTERC_driver
FORTERC_driver is a ROS driver for the FORTE-RC platform, implemented on the Arduino board. It deals with the omnidirectional kinematics, motor controllers and ultrasonic sensor readings. FORTERC_driver benefits from rosserial_arduino to publish and subscribe topics to the high-level layer.
Quick Start
Turn ON FORTE-RC and connect to its internal CPU (take a look here to know how to do so). Once FORTE-RC starts, simply run:
./forte_rc_bringup.sh
script, from forte_rc_robot/scripts folder. Or it is possible to launch it step-by-step description of how to start FORTERC_driver normal mode of operation is presented next.
To launch the serial bridge between the pc NUC and the ForteRC driver (Arduino Mega) and the 2 Hokuyo lasers:
roslaunch forte_rc_robot bring_up_forterc.launch
Launch the lasers merger:
roslaunch forte_rc_robot laser_merger.launch
Also if is necessary teleoperation with the wiimote, simply launch:
roslaunch forte_rc_robot teleop_wii_forterc.launch
To check if FORTERC_driver is on its normal mode of operation (i.e., publishing/subscribing topics through streaming mode), run check the topics published by the Arduino and echo the sonar readings as:
rostopic list rostopic echo sonars
Serial communication
The communication between the low-level (Arduino MEGA ADK ) and high-level (Intel NUC NUC5i5RYH) layers is made entirely via serial, as depicted above.
Tip: To list the all available usb ports:
ls -l /dev/forteRC*
ping-pong
The ping-pong communication is mainly used for debugging. It allows the user to test specific features of FORTE-RC, such as reading the ultrasonic sensors and the encoders, or even move the platform on a predefined path. Yet, the most relevant ping-pong commands are the ones that allow to start and stop the streaming process, which, on the other hand, enables the publish-subscribe ROS architecture on the Arduino board through rosserial_arduino.
All commands between CPU (NUC) and Arduino (uC) are sent and received in ASCII, starting with the '@' character and ending with the 'e' character. Note that some of the commands do not return any answer (NA). Next table presents all ping-pong commands implemented to date.
Name |
NUC > uC |
uC > NUC |
Description |
ACTION_START_STREAM |
@1e |
NA |
Start streaming publish/subscribe protocol |
ACTION_STOP_STREAM |
@2e |
NA |
Stop streaming publish/subscribe protocol |
ENCODER_TEST |
@3e |
@3<LFsec>,<RFsec>,<LBsec>,<RBsec>e |
Check if encoders work by moving each wheel consecutively for 2550 pulses, returning the number of seconds each wheel took to do so |
READ_ENCODERS |
@4e |
@4<LF>,<RF>,<LB>,<RB>e |
Read current value of encoders |
READ_SONARS_FRONT |
@5e |
@5<S1>,<S2>,<S3>,<S4>,<S5>e |
Read current value of front ultrasonic sensors in clockwise |
READ_SONARS_RIGHT |
@6e |
@6<S5>,<S6>,<S7>,<S8>,<S9>e |
Read current value of right ultrasonic sensors in clockwise |
READ_SONARS_BACK |
@7e |
@7<S9>,<S10>,<S11>,<S12>,<S13>e |
Read current value of back ultrasonic sensors in clockwise |
READ_SONARS_LEFT |
@8e |
@8<S13>,<S14>,<S15>,<S16>,<S1>e |
Read current value of left ultrasonic sensors in clockwise |
READ_SONARS_ALL |
@9e |
@9<S1>,<S2>,<S3>,<S4>,<S5>,<S6>,<S7>,<S8>,<S9>,<S10>,<S11>,<S12>,<S13>,<S14>,<S15>,<S16>e |
Read current value of all ultrasonic sensors in clockwise |
MOVE_PID |
@10,Vx,Vy,Vw,e |
NA |
Move the platform using the PID controller for |
MOVE_NOPID |
@11e |
NA |
Move the platform without using the PID controller for |
STOP_MOTORS |
@12e |
NA |
Stop motors |
ENCODERS_RESET |
@13e |
NA |
Reset encoders |
LED_STATE |
@14,<Rl>,<Gl>,<Bl>,<Rr>,<Gr>,<Br>e |
NA |
Control right and left RGB head LEDs |
GET_ODOM |
@15e |
@15<PoseX><PoseY><PoseW><VelX><VelY><VelW>e |
Display the pose of the robot (x,y,w) |
ODOM_RESET |
@16e |
NA |
Reset odometry pose to (0.0,0.0,0.0) |
LF = left-front | RF = right-front | LB = left-back | LF = left-front | sec = seconds | S1...16 = ultrasonic sensor | R = red (0-255) | G = green (0-255) | B = blue (0-255) | r = right | l = left
Streaming
As opposed to the ping-pong protocol exclusively designed for debugging and sporadic communication, the streaming protocol is required to keep a systematic communication with the ROS layer. To that end, the streaming benefits from rosserial_arduino to publish and subscribe topics. This is the core of the FORTERC_driver as it essentially connects FORTE-RC to the ROS framework. Although systematic, the streaming is aperiodic, i.e., some topics are published/subscribed whenever the data is ready, while some others are published/subscribed periodically. Yet, as a "safeguard mechanism", the timestamp from the high-level layer will be constantly monitored by the low-level layer, so as to ensure that the connection is well-established between both layers. Whenever the timestamp freezes for more than 500 milliseconds, FORTE-RC enters in the emergency mode state. Under the streaming protocol, the ROS-Arduino exchange the following messages.Subscribed Topics
cmd_vel (geometry_msgs/Twist)- Velocity commands to FORTE-RC.
- Control right and left RGB head LEDs.
Published Topics
odometry (nav_msgs/Odometry)- Odometry data from the robot.
- Range data from the array of 16 ultrasonic sensors.
Provided tf Transforms
odom → base_link- Odometry transform from odom frame to FORTE-RC's center.
- Computed footprint of FORTE-RC on the ground (z=0). This pose is always regarding the center of the platform.