• Diff for "rosserial_arduino/Tutorials/Servo Controller"
Differences between revisions 10 and 11
Revision 10 as of 2011-08-05 00:26:16
Size: 4100
Editor: AdamStambler
Comment:
Revision 11 as of 2011-08-05 04:19:30
Size: 4447
Editor: AdamStambler
Comment:
Deletions are marked like this. Additions are marked like this.
Line 46: Line 46:
/*
 * rosserial Servo Control Example
 *
 * This sketch demonstrates the control of hobby R/C servos
 * using ROS and the arduiono
 *
 * For the full tutorial write up, visit
 * www.ros.org/wiki/rosserial_arduino_demos
 *
 * For more information on the Arduino Servo Library
 * Checkout :
 * http://www.arduino.cc/en/Reference/Servo
 */
Line 48: Line 61:
Line 52: Line 66:
ros::NodeHandle nh;
Line 54: Line 70:
ROS_CALLBACK( servo_cb, std_msgs::UInt16, cmd_msg)
  

  servo.write(cmd_msg.data); //set servo angle, should be from 0-180
void servo_cb( const std_msgs::UInt16& cmd_msg){
  servo.write(cmd_msg.data); //set servo angle, should be from 0-180
Line 61: Line 75:
ros::NodeHandle nh;
ros::Subscriber sub("servo", &cmd_msg, servo_cb);
Line 64: Line 76:
ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
Line 66: Line 79:
 
Line 68: Line 80:
Line 71: Line 84:
  
Line 73: Line 85:
  

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Servo Controller Example

Description: Tutorial for controlling an R/C servo with rosserial and an Arduino

Tutorial Level:

Next Tutorial: IR Ranger

This tutorial explains how to control an R/C servo through ROS by using an Arduino and rosserial. This can be used to control a release mechanism, a cheap robot arm, ROS powered biped, or anything where you need a cheap actuator. The code provided is a very basic example and shows the control of a single hobby servo.

Hardware

arduino_servo.png

This example assumes that you have an Arduino and a hobby r/c servo. The r/c servo can be purchased from your local hobby shop, Towerhobbies, Sparkfun, etc.

The hobby servo r/c are great little actuators because they are relatively cheap (as low as $10) but contain a gear box and motor control electronics. They are controlled by sending a squarewave pulse of 1-2 milliseconds in width every 20 milliseconds. This typically moves the servo arm from 0-180 degrees. Hobby servo's come in a huge variety of sizes, torques, and angular precision.

Code

The code for this tutorial is made extremely simple through the use of the Arduino Servo library. The Servo Library handles all of the low level control to generate and maintain the servo pulses. All your code needs to do is specify the pin the servo is attached to and then write the angle to the servo object. Underneath, the Servo library uses the Arduino's built in timer interrupts to generate the correct pulses. In this example, we only control one servo, but the same library can be used to control up to 12 servos on most Arduino boards and 48 on the Arduino Mega.

Toggle line numbers
   1 /*
   2  * rosserial Servo Control Example
   3  *
   4  * This sketch demonstrates the control of hobby R/C servos
   5  * using ROS and the arduiono
   6  * 
   7  * For the full tutorial write up, visit
   8  * www.ros.org/wiki/rosserial_arduino_demos
   9  *
  10  * For more information on the Arduino Servo Library
  11  * Checkout :
  12  * http://www.arduino.cc/en/Reference/Servo
  13  */
  14 
  15 #include <WProgram.h>
  16 
  17 #include <Servo.h> 
  18 #include <ros.h>
  19 #include <std_msgs/UInt16.h>
  20 
  21 ros::NodeHandle  nh;
  22 
  23 Servo servo;
  24 
  25 void servo_cb( const std_msgs::UInt16& cmd_msg){
  26   servo.write(cmd_msg.data); //set servo angle, should be from 0-180  
  27   digitalWrite(13, HIGH-digitalRead(13));  //toggle led  
  28 }
  29 
  30 
  31 ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
  32 
  33 void setup(){
  34   pinMode(13, OUTPUT);
  35 
  36   nh.initNode();
  37   nh.subscribe(sub);
  38   
  39   servo.attach(9); //attach it to pin 9
  40 }
  41 
  42 void loop(){
  43   nh.spinOnce();
  44   delay(1);
  45 }

The key servo specific areas here are the fact that we made a global Servo object, attached to the correct arduino pin, and then on every servo topic call back, we write the servos new angle to the servo object.

Testing

First, startup your roscore and the rosserial python node in their own terminal windows.

roscore

rossrun rosserial_python serial_node.py /dev/ttyUSB0

Now, in a new terminal window, use rostopic pub to control your servo! Simply specify the angle from 0-180 and watch it move.

rostopic pub servo std_msgs/UInt16  <angle>

Wiki: rosserial_arduino/Tutorials/Servo Controller (last edited 2014-09-22 16:31:23 by AustinHendrix)