6. ROS Publisher¶
In this part of the Onboarding, you will let the car drive on the onboarding road.
You will do so by creating a publisher inside OnboardingNode
.
The publisher will be able to send messages that modify the car’s position.
6.1. Gazebo Plugins¶
Before getting started, we need to take a closer look at Gazebo. You already know how you can start a road in Gazebo and move the car around by hand. Gazebo also allows to programmatically change the position (and other properties) of models. In particular, plugins can be defined and attached to multiple models, sensors, and more, to modify a wide variety of properties.
If you take a look Dr.Drift’s model definition in simulation/src/gazebo_simulation/param/car_specs/dr_drift/model.urdf
you will find the line
<plugin name="model_plugin_link" filename="libmodel_plugin_link.so"/>
which equips the model_plugin_link.
The model_plugin_link is defined in gazebo_simulation. When attached to a model it listens to topics through which the pose and twist of the model can be modified. In this case, we only want to modify the car’s pose. The model_plugin_link ‘s topic for setting a pose is:
/simulation/gazebo/model/NAME_OF_MODEL/set_pose
Since the name of the car is dr_drift, our topic of interest is /simulation/gazebo/model/dr_drift/set_pose.
The new pose has to be sent as a
SetModelPose message.
It is defined in simulation/src/gazebo_simulation/msg/SetModelPose.msg
:
# The keys list is a list of integers specifying which variables should updated.
#
# Example
# -------
# If the message
#
# msg = SetModelPose()
# msg.keys = [SetModelPose.POSITION_X, SetModelPose.POSITION_Y]
# msg.values = [1,2]
#
# is received by a model plugin link, the corresponding model's
# position's x- and y-coordinate will be updated to x=1, y=2 while the z-coordinate remains
# unchanged.
#
uint8 POSITION_X = 0
uint8 POSITION_Y = 1
uint8 POSITION_Z = 2
uint8 ORIENTATION_W = 3
uint8 ORIENTATION_X = 4
uint8 ORIENTATION_Y = 5
uint8 ORIENTATION_Z = 6
int8[] keys
float32[] values
6.2. Create the Publisher¶
To control the car you will first need to add a publisher with topic /simulation/gazebo/model/dr_drift/set_pose
and message type SetModelPose to the OnboardingNode
:
Import ROS and SetModelPose at the top of the file:
import rospy
from gazebo_simulation.msg import SetModelPose
Create the publisher in
start()
:
self.pose_publisher = rospy.Publisher(
name="/simulation/gazebo/model/dr_drift/set_pose",
data_class=SetModelPose,
queue_size=1,
)
See http://docs.ros.org/lunar/api/rospy/html/rospy.topics.Publisher-class.html for a detailed explanation.
Unregister the publisher in stop():
self.pose_publisher.unregister()
6.3. Publish messages¶
The following lines show you how the publisher can be used to set the car’s x-coordinate x=0:
pose_msg = SetModelPose() # Create pose msg
# Append x coordinate to keys and values
pose_msg.keys.append(SetModelPose.POSITION_X)
pose_msg.values.append(0)
self.pose_publisher.publish(pose_msg)
Add these lines to steer()
to test if setting the x-coordinate works. Start Gazebo and the node with roslaunch.
roslaunch simulation_onboarding master.launch road:=onboarding_simple
When you try to move the car around it should always be set back onto the x-axis.
6.4. Drive along the road¶
You now know how to control the car’s x-coordinate.
Your Task
Make the car drive on the right side of the road with 1 m/s. Once it is at the end of the road, put it back to the beginning of the road!
After completing the task, don’t forget to commit and push your results!
Hint
Use rospy.Time.now().to_sec()
to get the current time in seconds.
The road is 5.8 meters long.