sr_movements.cpp
Go to the documentation of this file.
00001 
00029 #include "sr_movements/movement_from_image.hpp"
00030 #include "sr_movements/movement_publisher.hpp"
00031 
00032 #include <ros/ros.h>
00033 #include <iostream>
00034 
00035 
00036 int main(int argc, char *argv[])
00037 {
00038   ros::init(argc, argv, "sr_movements");
00039 
00040   ros::NodeHandle nh_tilde("~");
00041   std::string img_path;
00042 
00043   if( nh_tilde.getParam("image_path", img_path) )
00044   {
00045     shadowrobot::MovementFromImage mvt_im( img_path );
00046 
00047     double min, max, publish_rate;
00048     if( !nh_tilde.getParam("min", min) )
00049       min = 0.0;
00050     if( !nh_tilde.getParam("max", max) )
00051       max = 1.5;
00052     if( !nh_tilde.getParam("publish_rate", publish_rate) )
00053       publish_rate = 100.0;
00054 
00055     int repetition;
00056     if( !nh_tilde.getParam("repetition", repetition) )
00057       repetition = 1;
00058 
00059     int nb_mvt_step;
00060     if( !nh_tilde.getParam("nb_step", nb_mvt_step) )
00061       nb_mvt_step = 1000;
00062 
00063     std::string controller_type;
00064     if( !nh_tilde.getParam("msg_type", controller_type) )
00065       controller_type = "";
00066 
00067     shadowrobot::MovementPublisher mvt_pub( min, max, publish_rate, static_cast<unsigned int>(repetition),
00068                                             static_cast<unsigned int>(nb_mvt_step), controller_type);
00069     mvt_pub.add_movement( mvt_im );
00070 
00071     mvt_pub.start();
00072   }
00073   else
00074   {
00075     ROS_ERROR("No bitmap specified");
00076   }
00077   return 0;
00078 }
00079 
00080 
00081 
00082 /* For the emacs weenies in the crowd.
00083 Local Variables:
00084    c-basic-offset: 2
00085 End:
00086 */
00087 


sr_movements
Author(s): Ugo Cupcic / ugo@shadowrobot.com
autogenerated on Fri Jan 3 2014 12:08:55