Guide on how to do this
File -> Import Appliance
igvc.ova
fileImport
!cd catkin_ws
catkin_make
roscore
buzzsim
rosrun igvc_buzzsim buzzsim
rosrun
in detail:rosrun {package name} {executable name}
rosrun igvc_buzzsim buzzsim
buzzsim
executable which lives in the igvc_buzzsim
package/oswin/velocity
topic to make the turtle move./oswin/velocity
topic to control the turtle with our keyboard!teleop_twist_keyboard
to do that: rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=/oswin/velocity
teleop_twist_keyboard.py
from the package teleop_twist_keyboard
teleop_twist_keyboard
node publishes the velocity commands to the /oswin/velocity
topicbuzzsim
node subscribes to the /oswin/velocity
topic and uses the received messages to move the turtleteleop_twist_keyboard
publishes to a topic, it's a ROS Publisherbuzzsim
subscribes to a topic, so it's a ROS SubscriberROS Topics, Messages, Publishers and Subscribers are the core parts of ROS
rostopic
rostopic
:rostopic
# rostopic is a command-line tool for printing information about ROS Topics.
# Commands:
# rostopic bw display bandwidth used by topic
# rostopic delay display delay of topic from timestamp in header
# rostopic echo print messages to screen
# rostopic find find topics by type
# rostopic hz display publishing rate of topic
# rostopic info print information about active topic
# rostopic list list active topics
# rostopic pub publish data to topic
# rostopic type print topic or field type
#
# Type rostopic <command> -h for more detailed usage, e.g. 'rostopic echo -h'
rostopic list
rostopic list
rostopic list
# /oswin/velocity
# /rosout
# /rosout_agg
# /tf
/oswin/velocity
topic is shownrostopic info
/oswin/velocity
topic with rostopic info
: rostopic info /oswin/velocity
# Type: geometry_msgs/Twist
#
# Publishers:
# * /teleop_twist_keyboard (http://robojackets:46001/)
#
# Subscribers:
# * /buzzsimsim (http://robojackets:36899/)
geometry_msgs/Twist
geometry_msgs/Twist
, which comes from the package geometry_msgs
package from ROS, we can
lookup the definition in the ROS docs
(Google "geometry_msgs/Twist" and it should show up)What about looking at what's getting published on a topic?
rostopic echo
rostopic echo
to look at the messages on a topic:rostopic echo /oswin/velocity
# linear:
# x: 0.5
# y: 0.0
# z: 0.0
# angular:
# x: 0.0
# y: 0.0
# z: 0.0
# ---
rostopic pub
rostopic pub
teleop_twist_keyboard
rostopic pub
rostopic pub /oswin/velocity geometry_msgs/Twist "linear:
x: 1.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0"
rostopic pub /oswin/velocity
and then keep tabbingx
component of linear
and the z
component of angular
Now that we've seen how to use the rostopic
tool, let's look more at the ROS messages themselves. So far, we've
seen the geometry_msgs/Twist
message, but how do they work?
.msg
filesROS Messages are defined using .msg
files. For example, the
twist.msg
looks like:
# This expresses velocity in free space broken into its linear and angular parts.
Vector3 linear
Vector3 angular
Each line represents one field in the message, with the type on the left and the
name on the right. In this case, the twist.msg
message has two fields:
"linear" of type Vector3
, and "angular" of type Vector3
.
The Vector3
type that
this message refers to is another type that's defined
somewhere else:
# This represents a vector in free space.
# It is only meant to represent a direction. Therefore, it does not
# make sense to apply a translation to it (e.g., when applying a
# generic rigid transformation to a Vector3, tf2 will only apply the
# rotation). If you want your data to be translatable too, use the
# geometry_msgs/Point message instead.
float64 x
float64 y
float64 z
In general, messages are described by other messages within them.
Let's try writing our own ROS message now. Imagine that want to write a path planner node that publishes motor commands, and a motor controller node that subscribes to the motor commands.
We don't have a ROS message type for motor commands yet though, and so we need to make our own custom ROS message.
Some requirements for our message:
Write your ROS message in the file igvc_training_msgs/msg/motor_command.msg
.
Tips:
catkin_make
to compile the message!rostopic pub
and rostopic echo
to verify that your message works.This week, we learnt about:
rosrun <package-name> <node-name>
, ie. rosrun igvc_buzzsim buzzsim
teleop_twist_keyboard
rostopic
toolrostopic list
to list available topicsrostopic echo
to listen to topicsrostopic pub
to publish to topics.msg
fileThe presentation slides are available on github, under the ros-training repository on the RoboJackets github.
There's also a link to the markdown version of the same content in the README of the repository.
We'll be learning how to write ROS Publishers and Subscribers in C++
See you next week!