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("publish_rate", publish_rate) )
00049       publish_rate = 100.0;
00050 
00051     int repetition;
00052     if( !nh_tilde.getParam("repetition", repetition) )
00053       repetition = 1;
00054 
00055     int nb_mvt_step;
00056     if( !nh_tilde.getParam("nb_step", nb_mvt_step) )
00057       nb_mvt_step = 1000;
00058 
00059     std::string controller_type;
00060     if( !nh_tilde.getParam("msg_type", controller_type) )
00061       controller_type = "";
00062 
00063     std::string joint_name;
00064     if( !nh_tilde.getParam("joint_name", joint_name) )
00065     {
00066       //for compatibility, if no joint_name is provided, then we use the
00067       // provided min and max to instantiate the movement publisher
00068       // which will use the remapped topics.
00069       if( !nh_tilde.getParam("min", min) )
00070         min = 0.0;
00071       if( !nh_tilde.getParam("max", max) )
00072         max = 1.5;
00073 
00074       shadowrobot::MovementPublisher mvt_pub( min, max, publish_rate,
00075                                               static_cast<unsigned int>(repetition),
00076                                               static_cast<unsigned int>(nb_mvt_step),
00077                                               controller_type);
00078 
00079       mvt_pub.add_movement( mvt_im );
00080       mvt_pub.start();
00081     }
00082     else
00083     {
00084       //check if this is a test using gazebo
00085       bool testing;
00086       if( !nh_tilde.getParam("testing", testing))
00087         testing = false;
00088 
00089       //This is the new easier to implement version of the movement
00090       // publisher. Simply uses the name of the joint to instantiate
00091       // the MovementPublisher, grabbing min, max and topics from the
00092       // HandCommander.
00093       shadowrobot::MovementPublisher mvt_pub( joint_name, publish_rate,
00094                                               static_cast<unsigned int>(repetition),
00095                                               static_cast<unsigned int>(nb_mvt_step),
00096                                               controller_type, testing);
00097 
00098       mvt_pub.add_movement( mvt_im );
00099       mvt_pub.start();
00100     }
00101   }
00102   else
00103   {
00104     ROS_ERROR("No bitmap specified");
00105   }
00106   return 0;
00107 }
00108 
00109 
00110 
00111 /* For the emacs weenies in the crowd.
00112 Local Variables:
00113    c-basic-offset: 2
00114 End:
00115 */
00116 


sr_movements
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:25:49