movement_publisher.cpp
Go to the documentation of this file.
00001 
00026 #include "sr_movements/movement_publisher.hpp"
00027 
00028 #include <math.h>
00029 #include <sr_utilities/sr_math_utils.hpp>
00030 
00031 namespace shadowrobot
00032 {
00033   MovementPublisher::MovementPublisher(std::string joint_name, double rate, unsigned int repetition, unsigned int nb_mvt_step, std::string controller_type, bool testing, HandCommander* hand_commander)
00034     : joint_name_(joint_name), nh_tilde("~"), publishing_rate( rate ), repetition(repetition),
00035       min(0.0), max(1.5), last_target_(0.0), nb_mvt_step(nb_mvt_step),
00036       SError_(0.0), MSError_(0.0), n_samples_(0), controller_type(controller_type)
00037   {
00038     //this is a gazebo test, sleep for a long while to make sure gazebo is started.
00039     if(testing)
00040     {
00041       ROS_INFO("This is a test: sleeping 10 seconds for Gazebo to start.");
00042       sleep(20.0);
00043     }
00044 
00045     if( hand_commander != NULL )
00046       hand_commander_.reset(hand_commander);
00047     else
00048       hand_commander_.reset(new HandCommander());
00049 
00050     //if using the HandCommander, we're initialising the
00051     // vector of joints to send here, out of the loop.
00052     sr_robot_msgs::joint joint;
00053     joint.joint_name = joint_name_;
00054     joint_vector_.push_back(joint);
00055 
00056     std::pair<double, double> min_max = hand_commander_->get_min_max(joint_name_);
00057     min = min_max.first;
00058     max = min_max.second;
00059 
00060     std::string input = hand_commander_->get_controller_state_topic(joint_name_);
00061     subscribe_and_default_pub_(input);
00062   }
00063 
00064   MovementPublisher::MovementPublisher(double min_value, double max_value,
00065                                        double rate, unsigned int repetition,
00066                                        unsigned int nb_mvt_step, std::string controller_type)
00067     : nh_tilde("~"), publishing_rate( rate ), repetition(repetition),
00068       min(min_value), max(max_value), last_target_(0.0), nb_mvt_step(nb_mvt_step),
00069       SError_(0.0), MSError_(0.0), n_samples_(0), controller_type(controller_type)
00070   {
00071     pub = nh_tilde.advertise<std_msgs::Float64>("targets", 5);
00072 
00073     subscribe_and_default_pub_("inputs");
00074   }
00075 
00076   void MovementPublisher::subscribe_and_default_pub_(std::string input)
00077   {
00078     pub_mse_ = nh_tilde.advertise<std_msgs::Float64>("mse_out", 5);
00079 
00080     if(controller_type == "sr")
00081     {
00082       //nb_mvt_step is used to set the size of the buffer
00083       sub_ = nh_tilde.subscribe(input, nb_mvt_step, &MovementPublisher::sr_calculateErrorCallback, this);
00084     }
00085     else
00086     {
00087       //nb_mvt_step is used to set the size of the buffer
00088       sub_ = nh_tilde.subscribe(input, nb_mvt_step, &MovementPublisher::calculateErrorCallback, this);
00089     }
00090   }
00091 
00092   MovementPublisher::~MovementPublisher()
00093   {}
00094 
00095   void MovementPublisher::start()
00096   {
00097     double last_target = 0.0;
00098 
00099     for(unsigned int i_rep = 0; i_rep < repetition; ++i_rep)
00100     {
00101       for( unsigned int i=0; i<partial_movements.size(); ++i)
00102       {
00103         for(unsigned int j=0; j<nb_mvt_step; ++j)
00104         {
00105           if( !ros::ok() )
00106             return;
00107 
00108           //get the target
00109           msg.data = partial_movements[i].get_target( static_cast<double>(j) / static_cast<double>(nb_mvt_step));
00110 
00111           //there was not target -> resend the last target
00112           if( msg.data == -1.0 )
00113           {
00114             msg.data = last_target;
00115           }
00116           else
00117           {
00118             //interpolate to the correct range
00119             msg.data = min + msg.data * (max - min);
00120           }
00121           //publish the message
00122           publish_();
00123 
00124           //wait for a bit
00125           publishing_rate.sleep();
00126 
00127           ros::spinOnce();
00128 
00129           last_target = msg.data;
00130         }
00131       }
00132       //print the error information
00133       ROS_INFO_STREAM("MSE: " << MSError_ << " Error(deg): " << sr_math_utils::to_degrees( sqrt(MSError_) ) );
00134 
00135       //publish the error information
00136       msg.data = MSError_;
00137       pub_mse_.publish( msg );
00138 
00139       //Reset the error counter
00140       SError_ = 0.0;
00141       n_samples_ = 0;
00142     }
00143   }
00144 
00145   void MovementPublisher::sr_calculateErrorCallback(const sr_robot_msgs::JointControllerState::ConstPtr& msg)
00146   {
00147     double error = msg->set_point - msg->process_value;
00148     ROS_DEBUG_STREAM("Error: " << error);
00149     SError_ = SError_ + ( error * error );
00150     ROS_DEBUG_STREAM("SError: " << SError_);
00151     n_samples_++;
00152     ROS_DEBUG_STREAM("Samples: " << n_samples_);
00153     MSError_ = SError_ / ( static_cast<double>(n_samples_) );
00154     ROS_DEBUG_STREAM("MSe: " << MSError_);
00155   }
00156 
00157   void MovementPublisher::calculateErrorCallback(const control_msgs::JointControllerState::ConstPtr& msg)
00158   {
00159     double error = msg->set_point - msg->process_value;
00160     ROS_DEBUG_STREAM("Error: " << error);
00161     SError_ = SError_ + ( error * error );
00162     ROS_DEBUG_STREAM("SError: " << SError_);
00163     n_samples_++;
00164     ROS_DEBUG_STREAM("Samples: " << n_samples_);
00165     MSError_ = SError_ / ( static_cast<double>(n_samples_) );
00166     ROS_DEBUG_STREAM("MSe: " << MSError_);
00167   }
00168 
00169   void MovementPublisher::execute_step(int index_mvt_step, int index_partial_movement)
00170   {
00171     if( !ros::ok() )
00172       return;
00173 
00174     //get the target
00175     msg.data = partial_movements[index_partial_movement].get_target( static_cast<double>(index_mvt_step) / static_cast<double>(nb_mvt_step));
00176     //interpolate to the correct range
00177     msg.data = min + msg.data * (max - min);
00178 
00179     //there was not target -> resend the last target
00180     if( msg.data == -1.0 )
00181       msg.data = last_target_;
00182 
00183     publish_();
00184 
00185     //wait for a bit
00186     publishing_rate.sleep();
00187 
00188     last_target_ = msg.data;
00189   }
00190 
00191   void MovementPublisher::publish_()
00192   {
00193     //publish the message
00194     //use the default publisher if the HandCommander is not instantiated
00195     // (for compatibility reason)
00196     if( hand_commander_ == NULL )
00197       pub.publish( msg );
00198     //otherwise use the HandCommander
00199     else
00200     {
00201       joint_vector_[0].joint_target = sr_math_utils::to_degrees(msg.data);
00202       hand_commander_->sendCommands(joint_vector_);
00203     }
00204   }
00205 
00206   void MovementPublisher::stop()
00207   {}
00208 
00209   void MovementPublisher::add_movement(PartialMovement mvt)
00210   {
00211     partial_movements.push_back( mvt );
00212   }
00213 
00214   void MovementPublisher::set_publisher(ros::Publisher publisher)
00215   {
00216     pub = publisher;
00217   }
00218 
00219   void MovementPublisher::set_subscriber(ros::Subscriber subscriber)
00220   {
00221     sub_ = subscriber;
00222   }
00223 
00224   std::string MovementPublisher::get_subscriber_topic()
00225   {
00226     return hand_commander_->get_controller_state_topic(joint_name_);
00227   }
00228 }
00229 
00230 /* For the emacs weenies in the crowd.
00231 Local Variables:
00232    c-basic-offset: 2
00233 End:
00234 */


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