VEXProMotor13Subscribe.cpp
Go to the documentation of this file.
00001 /*
00002  * VEXProMotor13Subscribe.cpp
00003  * Control motor 13 speed by publishing the desired speed on a ros topic with e.g.
00004  * $ rostopic pub my_topic std_msgs/Int32 120
00005  */
00006 
00007 #include <ros.h>
00008 #include <std_msgs/Int32.h>
00009 #include <stdio.h>
00010 #include "qemotoruser.h"
00011 
00012 /*
00013  * Control motor 13 speed by publishing the desired speed on a ros topic with e.g.
00014  * $ rostopic pub my_topic std_msgs/Int32 120
00015  * The range of speeds is -255 to +255 (corresponding to full reverse to full forward).
00016  * Publish negative speeds using the syntax below:
00017  * $ rostopic pub my_topic std_msgs/Int32 -- -120
00018  * (This construct tells the shell to feed everything after -- directly to rostopic.)
00019  */
00020 
00021 ros::NodeHandle  nh;
00022 CQEMotorUser &motor = CQEMotorUser::GetRef();
00023 char *rosSrvrIp = "192.168.11.9";
00024 
00025 void messageCb(const std_msgs::Int32& motor13_msg){
00026         int speed = motor13_msg.data;
00027         printf("Received subscribed motor speed %d\n", speed);
00028     motor.SetPWM(0, speed);
00029 }
00030 ros::Subscriber<std_msgs::Int32> sub("motor13", messageCb );
00031 
00032 
00033 int main()
00034 {
00035         //nh.initNode();
00036         nh.initNode(rosSrvrIp);
00037         nh.subscribe(sub);
00038 
00039         while(1) {
00040                   sleep(1);
00041                   nh.spinOnce();
00042         }
00043 }


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Mon Oct 6 2014 07:10:50