ServoControl with two or more servos on arduino rosserial
*Hello friends. I want to make the example of Servo Control of Arduino, initially with two Servos, but have not successful. I tried to change the code this way but does not work.*
ros::NodeHandle nh;
Servo servo; Servo servo2;
void servocb( const stdmsgs::UInt16& cmdmsg){
servo.write(cmdmsg.data);
servo2.write(cmd_msg.data); //set servo angle, should be from 0-180
digitalWrite(13, HIGH-digitalRead(13)); //toggle led
}
ros::Subscriber
nh.initNode(); nh.subscribe(sub);
servo2.attach(7); servo.attach(9); }
void loop(){ nh.spinOnce(); delay(1); }
I hope someone can help me. Thanks for your time
Asked by andres1015415 on 2015-06-30 15:34:36 UTC
Answers
Here is an simple example:
#if (ARDUINO >= 100)
#include <Arduino.h>
#else
#include <WProgram.h>
#endif
#include <Servo.h>
#include <ros.h>
#include <std_msgs/UInt16.h>
ros::NodeHandle nh;
Servo servo1;
Servo servo2;
void servo1_cb( const std_msgs::UInt16& cmd_msg){
servo1.write(cmd_msg.data); //set servo angle, should be from 0-180
digitalWrite(13, HIGH-digitalRead(13)); //toggle led
}
void servo2_cb( const std_msgs::UInt16& cmd_msg){
servo2.write(cmd_msg.data); //set servo angle, should be from 0-180
//digitalWrite(13, HIGH-digitalRead(13)); //toggle led
}
ros::Subscriber<std_msgs::UInt16> sub1("servo1", servo1_cb);
ros::Subscriber<std_msgs::UInt16> sub2("servo2", servo2_cb);
void setup(){
pinMode(13, OUTPUT);
nh.initNode();
nh.subscribe(sub1);
nh.subscribe(sub2);
servo1.attach(9); //attach it to pin 9
servo2.attach(10);//attach it to pin10
}
void loop(){
nh.spinOnce();
delay(20);
}
publisher:
rostopic pub servo1 std_msgs/UInt16 <angle1> & rostopic pub servo2 std_msgs/UInt16 <angle2>
Asked by Chuong Nguyen on 2015-10-12 10:00:41 UTC
Comments
Another Example uses MutiArray
Asked by Chuong Nguyen on 2015-10-12 10:32:40 UTC
have you a code o node that publish angle ?
Asked by Emilien on 2016-05-03 13:44:21 UTC
Comments