movement_publisher.hpp
Go to the documentation of this file.
00001 
00027 #ifndef _MOVEMENT_PUBLISHER_HPP_
00028 #define _MOVEMENT_PUBLISHER_HPP_
00029 
00030 #include <ros/ros.h>
00031 #include <boost/thread.hpp>
00032 
00033 #include <std_msgs/Float64.h>
00034 #include "sr_movements/partial_movement.hpp"
00035 #include <control_msgs/JointControllerState.h>
00036 #include <sr_robot_msgs/JointControllerState.h>
00037 #include <math.h>
00038 #include <sr_hand/hand_commander.hpp>
00039 
00040 namespace shadowrobot
00041 {
00042   class MovementPublisher
00043   {
00044   public:
00057     MovementPublisher( std::string joint_name, double rate=100.0,
00058                        unsigned int repetition = 1, unsigned int nb_mvt_step = 1000 ,
00059                        std::string controller_type = "", bool testing = false,
00060                        HandCommander* hand_commander = NULL);
00061 
00062     MovementPublisher( double min_value = 0.0, double max_value = 1.5,
00063                        double rate=100.0, unsigned int repetition = 1,
00064                        unsigned int nb_mvt_step = 1000 , std::string controller_type = "");
00065 
00066     virtual ~MovementPublisher();
00067 
00068     void start();
00069     void stop();
00070 
00077     void sr_calculateErrorCallback(const sr_robot_msgs::JointControllerState::ConstPtr& msg);
00078 
00085     void calculateErrorCallback(const control_msgs::JointControllerState::ConstPtr& msg);
00086 
00091     void execute_step(int index_mvt_step, int index_partial_movement);
00092 
00093     void add_movement(PartialMovement mvt);
00094 
00095     void set_publisher(ros::Publisher publisher);
00096     void set_subscriber(ros::Subscriber subscriber);
00097 
00098     std::string get_subscriber_topic();
00099 
00100   protected:
00108     void subscribe_and_default_pub_(std::string input);
00109 
00116     void publish_();
00117 
00118     boost::shared_ptr<HandCommander> hand_commander_;
00119     std::string joint_name_;
00120 
00121     std::vector<PartialMovement> partial_movements;
00122     ros::NodeHandle nh_tilde;
00123     ros::Publisher pub;
00124     ros::Publisher pub_mse_;
00125     ros::Subscriber sub_;
00126 
00127     ros::Rate publishing_rate;
00128     unsigned int repetition;
00129     double min, max;
00130 
00131     std_msgs::Float64 msg;
00132     std::vector<sr_robot_msgs::joint> joint_vector_;
00133     double last_target_;
00134 
00135     unsigned int nb_mvt_step;
00136     double SError_;
00137     double MSError_;
00138     unsigned int n_samples_;
00139     std::string controller_type;
00140   };
00141 }
00142 
00143 /* For the emacs weenies in the crowd.
00144 Local Variables:
00145    c-basic-offset: 2
00146 End:
00147 */
00148 
00149 #endif


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