$search
00001 /* 00002 * VEXProServoSubscribe.cpp 00003 * 00004 * Created on: Jul 12, 2012 00005 * Author: bouchier 00006 * Drives a servo or motor on VEXPro motor1 connection to the requested value: 0 - 255 00007 * that is received on subscribed topic servo1 00008 */ 00009 00010 #include <ros.h> 00011 #include <std_msgs/Int32.h> 00012 #include <iostream> 00013 #include <qeservo.h> 00014 using namespace std; 00015 00016 ros::NodeHandle nh; 00017 CQEServo &servo = CQEServo::GetRef(); 00018 char *rosSrvrIp = "192.168.15.149"; 00019 00020 void messageCb(const std_msgs::Int32& servo1_msg){ 00021 int position = servo1_msg.data; 00022 printf("Received subscribed servo position %d\n", position); 00023 servo.SetCommand(0, position); 00024 } 00025 ros::Subscriber<std_msgs::Int32> sub("servo1", messageCb ); 00026 00027 int main() { 00028 //nh.initNode(); 00029 nh.initNode(rosSrvrIp); 00030 nh.subscribe(sub); 00031 00032 while(1) { 00033 sleep(1); 00034 nh.spinOnce(); 00035 } 00036 }