Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #include <ros.h>
00008 #include <std_msgs/Int32.h>
00009 #include <stdio.h>
00010 #include "qemotoruser.h"
00011
00012
00013
00014
00015
00016
00017
00018
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
00036 nh.initNode(rosSrvrIp);
00037 nh.subscribe(sub);
00038
00039 while(1) {
00040 sleep(1);
00041 nh.spinOnce();
00042 }
00043 }