Go to the documentation of this file.00001 #include "ros/ros.h"
00002 #include <openreroc_pwm/openreroc_pwm.h>
00003
00004 int main(int argc, char **argv)
00005 {
00006 ros::init(argc, argv, "sample_input_openreroc_pwm");
00007
00008 ros::NodeHandle n;
00009 ros::Publisher pub_openreroc_pwm = n.advertise<openreroc_pwm::openreroc_pwm>("openreroc_pwm", 1000);
00010
00011 ros::Rate loop_rate(1);
00012 openreroc_pwm::openreroc_pwm msg;
00013
00014 int count = 0;
00015 while (ros::ok())
00016 {
00017
00018 unsigned char dir_left;
00019 unsigned int para_left;
00020 unsigned char dir_right;
00021 unsigned int para_right;
00022 printf("type parameter [dir_left] [para_left] [dir_right] [para_right]\n");
00023 scanf("%u %u %u %u",&dir_left, ¶_left ,&dir_right, ¶_right);
00024
00025 msg.dir_left = dir_left;
00026 msg.para_left = para_left;
00027 msg.dir_right = dir_right;
00028 msg.para_right = para_right;
00029
00030 pub_openreroc_pwm.publish(msg);
00031 ros::spinOnce();
00032 }
00033 return 0;
00034 }