movement_publisher.cpp
Go to the documentation of this file.
1 
27 #include <math.h>
28 #include <utility>
29 #include <string>
30 #include <algorithm>
31 
33 #include <sr_utilities/sr_math_utils.hpp>
34 
35 namespace shadowrobot
36 {
37  MovementPublisher::MovementPublisher(std::string joint_name, double rate,
38  unsigned int repetition, unsigned int nb_mvt_step,
39  std::string controller_type, bool testing, HandCommander* hand_commander)
40  : joint_name_(joint_name), nh_tilde("~"), publishing_rate(rate), repetition(repetition),
41  min(0.0), max(1.5), last_target_(0.0), nb_mvt_step(nb_mvt_step),
42  SError_(0.0), MSError_(0.0), n_samples_(0), controller_type(controller_type)
43  {
44  // this is a gazebo test, sleep for a long while to make sure gazebo is started.
45  if (testing)
46  {
47  ROS_INFO("This is a test: sleeping 10 seconds for Gazebo to start.");
48  sleep(20.0);
49  }
50 
51  if (hand_commander != NULL)
52  hand_commander_.reset(hand_commander);
53  else
54  hand_commander_.reset(new HandCommander());
55 
56  // if using the HandCommander, we're initialising the
57  // vector of joints to send here, out of the loop.
58  sr_robot_msgs::joint joint;
59  joint.joint_name = joint_name_;
60  joint_vector_.push_back(joint);
61 
62  std::pair<double, double> min_max = hand_commander_->get_min_max(joint_name_);
63  min = min_max.first;
64  max = min_max.second;
65 
66  std::string input = hand_commander_->get_controller_state_topic(joint_name_);
68  }
69 
70  MovementPublisher::MovementPublisher(double min_value, double max_value,
71  double rate, unsigned int repetition,
72  unsigned int nb_mvt_step, std::string controller_type)
73  : nh_tilde("~"), publishing_rate(rate), repetition(repetition),
74  min(min_value), max(max_value), last_target_(0.0), nb_mvt_step(nb_mvt_step),
75  SError_(0.0), MSError_(0.0), n_samples_(0), controller_type(controller_type)
76  {
77  pub = nh_tilde.advertise<std_msgs::Float64>("targets", 5);
78 
80  }
81 
83  {
84  pub_mse_ = nh_tilde.advertise<std_msgs::Float64>("mse_out", 5);
85 
86  if (controller_type == "sr")
87  {
88  // nb_mvt_step is used to set the size of the buffer
90  }
91  else
92  {
93  // nb_mvt_step is used to set the size of the buffer
95  }
96  }
97 
99  {}
100 
102  {
103  double last_target = 0.0;
104 
105  for (unsigned int i_rep = 0; i_rep < repetition; ++i_rep)
106  {
107  for (unsigned int i = 0; i < partial_movements.size(); ++i)
108  {
109  for (unsigned int j = 0; j < nb_mvt_step; ++j)
110  {
111  if (!ros::ok())
112  return;
113 
114  // get the target
115  msg.data = partial_movements[i].get_target(static_cast<double>(j) / static_cast<double>(nb_mvt_step));
116 
117  // there was not target -> resend the last target
118  if (msg.data == -1.0)
119  {
120  msg.data = last_target;
121  }
122  else
123  {
124  // interpolate to the correct range
125  msg.data = min + msg.data * (max - min);
126  }
127  // publish the message
128  publish_();
129 
130  // wait for a bit
132 
133  ros::spinOnce();
134 
135  last_target = msg.data;
136  }
137  }
138  // print the error information
139  ROS_INFO_STREAM("MSE: " << MSError_ << " Error(deg): " << sr_math_utils::to_degrees(sqrt(MSError_)));
140 
141  // publish the error information
142  msg.data = MSError_;
144 
145  // Reset the error counter
146  SError_ = 0.0;
147  n_samples_ = 0;
148  }
149  }
150 
151  void MovementPublisher::sr_calculateErrorCallback(const sr_robot_msgs::JointControllerState::ConstPtr& msg)
152  {
153  double error = msg->set_point - msg->process_value;
154  ROS_DEBUG_STREAM("Error: " << error);
155  SError_ = SError_ + (error * error);
156  ROS_DEBUG_STREAM("SError: " << SError_);
157  n_samples_++;
158  ROS_DEBUG_STREAM("Samples: " << n_samples_);
159  MSError_ = SError_ / (static_cast<double>(n_samples_));
160  ROS_DEBUG_STREAM("MSe: " << MSError_);
161  }
162 
163  void MovementPublisher::calculateErrorCallback(const control_msgs::JointControllerState::ConstPtr& msg)
164  {
165  double error = msg->set_point - msg->process_value;
166  ROS_DEBUG_STREAM("Error: " << error);
167  SError_ = SError_ + (error * error);
168  ROS_DEBUG_STREAM("SError: " << SError_);
169  n_samples_++;
170  ROS_DEBUG_STREAM("Samples: " << n_samples_);
171  MSError_ = SError_ / (static_cast<double>(n_samples_));
172  ROS_DEBUG_STREAM("MSe: " << MSError_);
173  }
174 
175  void MovementPublisher::execute_step(int index_mvt_step, int index_partial_movement)
176  {
177  if (!ros::ok())
178  return;
179 
180  // get the target
181  msg.data = partial_movements[index_partial_movement].get_target(
182  static_cast<double>(index_mvt_step) / static_cast<double>(nb_mvt_step));
183  // interpolate to the correct range
184  msg.data = min + msg.data * (max - min);
185 
186  // there was not target -> resend the last target
187  if (msg.data == -1.0)
188  msg.data = last_target_;
189 
190  publish_();
191 
192  // wait for a bit
194 
195  last_target_ = msg.data;
196  }
197 
199  {
200  // publish the message
201  // use the default publisher if the HandCommander is not instantiated
202  // (for compatibility reason)
203  if (hand_commander_ == NULL)
204  pub.publish(msg);
205  // otherwise use the HandCommander
206  else
207  {
208  joint_vector_[0].joint_target = sr_math_utils::to_degrees(msg.data);
209  hand_commander_->sendCommands(joint_vector_);
210  }
211  }
212 
214  {}
215 
217  {
218  partial_movements.push_back(mvt);
219  }
220 
222  {
223  pub = publisher;
224  }
225 
227  {
228  sub_ = subscriber;
229  }
230 
232  {
233  return hand_commander_->get_controller_state_topic(joint_name_);
234  }
235 } // namespace shadowrobot
236 
237 /* For the emacs weenies in the crowd.
238 Local Variables:
239  c-basic-offset: 2
240 End:
241 */
MovementPublisher(std::string joint_name, double rate=100.0, unsigned int repetition=1, unsigned int nb_mvt_step=1000, std::string controller_type="", bool testing=false, HandCommander *hand_commander=NULL)
void execute_step(int index_mvt_step, int index_partial_movement)
void set_subscriber(ros::Subscriber subscriber)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void add_movement(PartialMovement mvt)
Publishes a sequence of movements.
boost::shared_ptr< HandCommander > hand_commander_
void subscribe_and_default_pub_(std::string input)
void calculateErrorCallback(const control_msgs::JointControllerState::ConstPtr &msg)
std::vector< PartialMovement > partial_movements
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
bool sleep()
void set_publisher(ros::Publisher publisher)
#define ROS_INFO_STREAM(args)
std::vector< sr_robot_msgs::joint > joint_vector_
ROSCPP_DECL void spinOnce()
void sr_calculateErrorCallback(const sr_robot_msgs::JointControllerState::ConstPtr &msg)


sr_movements
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:50:46