So, the topic /cmd_vel
topic should have the message type Twist
Looking at the message description, we can see that each incoming message should have a linear
component, for the (x,y,z) velocities, and an angular component for the angular rate about the (x,y,z) axes.
I'm going to give you some example code in Python, but this could just as easily be done in C++.
#!/usr/bin/env python
import roslib; roslib.load_manifest('YOUR_PACKAGE_NAME_HERE')
import rospy
import tf.transformations
from geometry_msgs.msg import Twist
def callback(msg):
rospy.loginfo("Received a /cmd_vel message!")
rospy.loginfo("Linear Components: [%f, %f, %f]"%(msg.linear.x, msg.linear.y, msg.linear.z))
rospy.loginfo("Angular Components: [%f, %f, %f]"%(msg.angular.x, msg.angular.y, msg.angular.z))
# Do velocity processing here:
# Use the kinematics of your robot to map linear and angular velocities into motor commands
v_l = ...
v_r = ...
# Then set your wheel speeds (using wheel_left and wheel_right as examples)
wheel_left.set_speed(v_l)
wheel_right.set_speed(v_r)
def listener():
rospy.init_node('cmd_vel_listener')
rospy.Subscriber("/cmd_vel", Twist, callback)
rospy.spin()
if __name__ == '__main__':
listener()
In this example, we create a node called cmd_vel_listener
that subscribes to the /cmd_vel
topic. We can then create a callback function (called callback
), which accepts the message as a parameter msg
.
From here, it is as simple as reading the named fields from the message, and using that data in whatever way that you want in your application.
Hope this helps.
I not very familiar with Python. can you give me in C++ so i can directly compile it into arduino IDE ? Or you have servo motor subscriber example which is controlling by using ultrasonic sensor as a publisher ? Thnks in advance
From the tutorials, Servo Example: http://www.ros.org/wiki/rosserial_arduino/Tutorials/Servo%20Controller
From the tutorials: Rangefinder example: http://www.ros.org/wiki/rosserial_arduino/Tutorials/SRF08%20Ultrasonic%20Range%20Finder
Thanks, but i already done this rosserial tutorials and it works perfectly. The main problem is to mix the Servo, Rangefinder, arduino and my main processor in C language. My main goal is to build an normal arduino obstacle avoidance robot which is implement by ROS.
I believe, many people out there is not clear about this 'mixing' up method even though its a simple robot project. Sorry about that :)
So are you trying to do all of this on an Arduino? Or is there some interface to another computer?
Have you taken a look at this https://github.com/hbrobotics/ros_arduino_bridge/ All the base code is done so it makes it much easier to get started and you can easily add support for different hardware.The readme gives a twist example, and it just enough to start playing with twist messages.