pr2_odometry.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 /*
35  * Author: Sachin Chitta and Matthew Piccoli
36  */
37 
40 
42 
43 namespace controller {
44 
45 
46  const static double ODOMETRY_THRESHOLD = 1e-4;
47  const static double MAX_ALLOWABLE_SVD_TIME = 3e-4;
48 
50  {
51  sequence_ = 0;
52  }
53 
55  {
56  }
57 
59  {
60  node_ = node;
61 
62  std::string prefix_param;
63  node.searchParam("tf_prefix", prefix_param);
64  node.getParam(prefix_param, tf_prefix_);
65 
66  node.param<double>("odometer/initial_distance", odometer_distance_, 0.0);
67  node.param<double>("odometer/initial_angle", odometer_angle_, 0.0);
68  node.param<double>("odom/initial_x", odom_.x, 0.0);
69  node.param<double>("odom/initial_y", odom_.y, 0.0);
70  node.param<double>("odom/initial_yaw", odom_.z, 0.0);
71 
72  node.param<bool>("publish_tf", publish_tf_, true);
73  node.param<int> ("ils_max_iterations", ils_max_iterations_, 3);
74  node.param<std::string> ("odom_frame", odom_frame_, "odom");
75  node.param<std::string> ("base_footprint_frame", base_footprint_frame_,
76  "base_footprint");
77  node.param<std::string> ("base_link_frame", base_link_frame_, "base_link");
78 
79  node.param<double> ("x_stddev", sigma_x_, 0.002);
80  node.param<double> ("y_stddev", sigma_y_, 0.002);
81  node.param<double> ("rotation_stddev", sigma_theta_, 0.017);
82 
83  node.param<double> ("cov_xy", cov_x_y_, 0.0);
84  node.param<double> ("cov_xrotation", cov_x_theta_, 0.0);
85  node.param<double> ("cov_yrotation", cov_y_theta_, 0.0);
86  node.param<bool> ("verbose", verbose_, false);
87 
88  node.param<double>("odom_publish_rate", odom_publish_rate_, 30.0);
89  node.param<double>("odometer_publish_rate", odometer_publish_rate_, 1.0);
90  node.param<double>("state_publish_rate", state_publish_rate_, 1.0);
91  node.param<double>("caster_calibration_multiplier",
93 
94  if(odom_publish_rate_ <= 0.0) {
96  publish_odom_ = false;
97  } else {
99  publish_odom_ = true;
100  }
101 
102  if(odometer_publish_rate_ <= 0.0) {
104  publish_odometer_ = false;
105  } else {
107  publish_odometer_ = true;
108  }
109 
110  if(state_publish_rate_ <= 0.0) {
112  publish_state_ = false;
113  } else {
115  publish_state_ = true;
116  }
117 
118 
119 
120  if(!base_kin_.init(robot_state, node_))
121  return false;
122 
123  for(int i = 0; i < base_kin_.num_casters_; ++i) {
124  if(!base_kin_.caster_[i].joint_->calibrated_) {
125  ROS_ERROR("The Base odometry could not start because the casters were "
126  "not calibrated. Relaunch the odometry after you see the caster "
127  "calibration finish.");
128  return false; // Casters are not calibrated
129  }
130  }
131 
132  cbv_rhs_.setZero();
133  cbv_lhs_.setZero();
134  cbv_soln_.setZero();
135  fit_lhs_.setZero();
136  fit_rhs_.setZero();
137  fit_soln_.setZero();
138  fit_residual_.setZero();
139  odometry_residual_.setZero();
140  weight_matrix_.setIdentity();
141 
142  if(verbose_) {
145  debug_publisher_->msg_.timing.resize(3);
146  matrix_publisher_->msg_.m.resize(48);
147  }
148 
153 
154  transform_publisher_->msg_.transforms.resize(1);
155 
156  state_publisher_->msg_.wheel_link_names.resize(base_kin_.num_wheels_);
157  state_publisher_->msg_.drive_constraint_errors.resize(base_kin_.num_wheels_);
158  state_publisher_->msg_.longitudinal_slip_constraint_errors.resize(base_kin_.num_wheels_);
159  return true;
160  }
161 
163  {
164  return true;
165 
166  for(int i=0; i < base_kin_.num_wheels_; i++)
167  if(std::isnan(base_kin_.wheel_[i].joint_->velocity_) ||
168  std::isnan(base_kin_.wheel_[i].joint_->velocity_))
169  return false;
170 
171  for(int i=0; i < base_kin_.num_casters_; i++)
172  if(std::isnan(base_kin_.caster_[i].joint_->velocity_) ||
173  std::isnan(base_kin_.caster_[i].joint_->velocity_))
174  return false;
175 
176  return true;
177  }
178 
179  void Pr2Odometry::starting()
180  {
187  }
188 
189  void Pr2Odometry::update()
190  {
191  if(!isInputValid()) {
192  if(verbose_) {
193  debug_publisher_->msg_.input_valid = false;
194  ROS_DEBUG("Odometry:: Input velocities are invalid");
195  }
196  return;
197  } else {
198  if(verbose_)
199  debug_publisher_->msg_.input_valid = true;
200  }
201 
203  ros::Time update_start = ros::Time::now();
204  updateOdometry();
205  double update_time = (ros::Time::now()-update_start).toSec();
206  ros::Time publish_start = ros::Time::now();
207 
208  if(publish_odom_)
209  publish();
212  if(publish_state_)
213  publishState();
214  if(publish_tf_)
216 
217  double publish_time = (ros::Time::now()-publish_start).toSec();
218  if(verbose_) {
219  debug_publisher_->msg_.timing[0] = update_time;
220  debug_publisher_->msg_.timing[1] = publish_time;
222  debug_publisher_->msg_.sequence = sequence_;
223  if(debug_publisher_->trylock()) {
224  debug_publisher_->unlockAndPublish();
225  }
226  }
228  sequence_++;
229  }
230 
232  {
233  double dt = (current_time_ - last_time_).toSec();
234  double theta = odom_.z;
235  double costh = cos(theta);
236  double sinth = sin(theta);
237 
239 
240  double odom_delta_x = (odom_vel_.linear.x * costh -
241  odom_vel_.linear.y * sinth) * dt;
242  double odom_delta_y = (odom_vel_.linear.x * sinth +
243  odom_vel_.linear.y * costh) * dt;
244  double odom_delta_th = odom_vel_.angular.z * dt;
245 
246  odom_.x += odom_delta_x;
247  odom_.y += odom_delta_y;
248  odom_.z += odom_delta_th;
249 
250  ROS_DEBUG("Odometry:: Position: %f, %f, %f",odom_.x,odom_.y,odom_.z);
251 
252  odometer_distance_ += sqrt(odom_delta_x * odom_delta_x +
253  odom_delta_y * odom_delta_y);
254  odometer_angle_ += fabs(odom_delta_th);
255  }
256 
257  void Pr2Odometry::getOdometry(geometry_msgs::Point &odom,
258  geometry_msgs::Twist &odom_vel)
259  {
260  odom = odom_;
261  odom_vel = odom_vel_;
262  return;
263  }
264 
265  void Pr2Odometry::getOdometryMessage(nav_msgs::Odometry &msg)
266  {
267  msg.header.frame_id = odom_frame_;
268  msg.header.stamp = current_time_;
269  msg.pose.pose.position.x = odom_.x;
270  msg.pose.pose.position.y = odom_.y;
271  msg.pose.pose.position.z = 0.0;
272 
273  tf::Quaternion quat_trans;
274  quat_trans.setRPY(0.0, 0.0, odom_.z);
275  msg.pose.pose.orientation.x = quat_trans.x();
276  msg.pose.pose.orientation.y = quat_trans.y();
277  msg.pose.pose.orientation.z = quat_trans.z();
278  msg.pose.pose.orientation.w = quat_trans.w();
279 
280  msg.twist.twist = odom_vel_;
282  }
283 
284  void Pr2Odometry::populateCovariance(const double &residual,
285  nav_msgs::Odometry &msg)
286  {
287  double odom_multiplier = 1.0;
288 
289  if(fabs(odom_vel_.linear.x) <= 1e-8 &&
290  fabs(odom_vel_.linear.y) <= 1e-8 &&
291  fabs(odom_vel_.angular.z) <= 1e-8) {
292  //nav_msgs::Odometry has a 6x6 covariance matrix
293  msg.pose.covariance[0] = 1e-12;
294  msg.pose.covariance[7] = 1e-12;
295  msg.pose.covariance[35] = 1e-12;
296 
297  msg.pose.covariance[1] = 1e-12;
298  msg.pose.covariance[6] = 1e-12;
299 
300  msg.pose.covariance[31] = 1e-12;
301  msg.pose.covariance[11] = 1e-12;
302 
303  msg.pose.covariance[30] = 1e-12;
304  msg.pose.covariance[5] = 1e-12;
305  } else {
306  //nav_msgs::Odometry has a 6x6 covariance matrix
307  msg.pose.covariance[0] = odom_multiplier*pow(sigma_x_,2);
308  msg.pose.covariance[7] = odom_multiplier*pow(sigma_y_,2);
309  msg.pose.covariance[35] = odom_multiplier*pow(sigma_theta_,2);
310 
311  msg.pose.covariance[1] = odom_multiplier*cov_x_y_;
312  msg.pose.covariance[6] = odom_multiplier*cov_x_y_;
313 
314  msg.pose.covariance[31] = odom_multiplier*cov_y_theta_;
315  msg.pose.covariance[11] = odom_multiplier*cov_y_theta_;
316 
317  msg.pose.covariance[30] = odom_multiplier*cov_x_theta_;
318  msg.pose.covariance[5] = odom_multiplier*cov_x_theta_;
319  }
320 
321  msg.pose.covariance[14] = DBL_MAX;
322  msg.pose.covariance[21] = DBL_MAX;
323  msg.pose.covariance[28] = DBL_MAX;
324 
325  msg.twist.covariance = msg.pose.covariance;
326  }
327 
328 
329  void Pr2Odometry::getOdometry(double &x, double &y, double &yaw,
330  double &vx, double &vy, double &vw)
331  {
332  x = odom_.x;
333  y = odom_.y;
334  yaw = odom_.z;
335  vx = odom_vel_.linear.x;
336  vy = odom_vel_.linear.y;
337  vw = odom_vel_.angular.z;
338  }
339 
341  {
342  double steer_angle, wheel_speed, costh, sinth;
343  geometry_msgs::Twist caster_local_velocity;
344  geometry_msgs::Twist wheel_local_velocity;
345  geometry_msgs::Point wheel_position;
346  for(int i = 0; i < base_kin_.num_wheels_; i++) {
347  base_kin_.wheel_[i].updatePosition();
348  steer_angle = base_kin_.wheel_[i].parent_->joint_->position_;//I'm coming out properly!
349  wheel_position = base_kin_.wheel_[i].position_;
350  costh = cos(steer_angle);
351  sinth = sin(steer_angle);
352  wheel_speed = 0;
353  wheel_speed = getCorrectedWheelSpeed(i);
354  ROS_DEBUG("Odometry:: Wheel: %s, angle: %f, speed: %f",
355  base_kin_.wheel_[i].link_name_.c_str(),steer_angle,wheel_speed);
356  cbv_rhs_(i * 2, 0) = base_kin_.wheel_[i].wheel_radius_ * wheel_speed;
357  cbv_rhs_(i * 2 + 1, 0) = 0;
358 
359  cbv_lhs_(i * 2, 0) = costh;
360  cbv_lhs_(i * 2, 1) = sinth;
361  cbv_lhs_(i * 2, 2) = -costh * wheel_position.y +
362  sinth * wheel_position.x;
363  cbv_lhs_(i * 2 + 1, 0) = -sinth;
364  cbv_lhs_(i * 2 + 1, 1) = costh;
365  cbv_lhs_(i * 2 + 1, 2) = sinth * wheel_position.y +
366  costh * wheel_position.x;
367  }
369 
371  odometry_residual_max_ = odometry_residual_.array().abs().maxCoeff();
372  ROS_DEBUG("Odometry:: base velocity: %f, %f, %f",
373  cbv_soln_(0,0), cbv_soln_(1,0), cbv_soln_(2,0));
374  ROS_DEBUG("Odometry:: odometry residual: %f",odometry_residual_max_);
375  odom_vel_.linear.x = cbv_soln_(0, 0);
376  odom_vel_.linear.y = cbv_soln_(1, 0);
377  odom_vel_.angular.z = cbv_soln_(2, 0);
378  }
379 
380  double Pr2Odometry::getCorrectedWheelSpeed(const int &index)
381  {
382  double wheel_speed;
383  geometry_msgs::Twist caster_local_vel;
384  geometry_msgs::Twist wheel_local_vel;
385  caster_local_vel.angular.z = base_kin_.wheel_[index].parent_->joint_->velocity_*caster_calibration_multiplier_;
386  wheel_local_vel = base_kin_.pointVel2D(base_kin_.wheel_[index].offset_, caster_local_vel);
387  wheel_speed = base_kin_.wheel_[index].joint_->velocity_ -
388  wheel_local_vel.linear.x / (base_kin_.wheel_[index].wheel_radius_);
389  return wheel_speed;
390  }
391 
393  const OdomMatrix16x1 &rhs, const int &max_iter)
394  {
395  weight_matrix_.setIdentity();
396  double svd_time = 0.0;
397  bool pub_matrix = false;
398  ros::Time tmp_start;
399 
400  for(int i = 0; i < max_iter; i++) {
401  fit_lhs_ = weight_matrix_ * lhs;
402  fit_rhs_ = weight_matrix_ * rhs;
403 
404  if(verbose_)
405  tmp_start = ros::Time::now();
406  Eigen::JacobiSVD<Eigen::MatrixXf> svdOfFit(fit_lhs_,Eigen::ComputeThinU|Eigen::ComputeThinV);
407  fit_soln_ = svdOfFit.solve(fit_rhs_);
408 
409  ROS_DEBUG("Odometry:: fit_soln_: %f %f %f",
410  fit_soln_(0,0), fit_soln_(1,0), fit_soln_(2,0));
411 
412  if(verbose_) {
413  svd_time = (ros::Time::now()-tmp_start).toSec();
414  debug_publisher_->msg_.timing[2] = svd_time;
415  if(svd_time > MAX_ALLOWABLE_SVD_TIME) {
416  for(int k = 0; k < 48; k++) {
417  int i_index = k/3;
418  int j_index = k - i_index *3;
419  matrix_publisher_->msg_.m[i] = fit_lhs_(i_index,j_index);
420  }
421  pub_matrix = true;
422  }
423  if(pub_matrix) {
424  if(matrix_publisher_->trylock())
425  matrix_publisher_->unlockAndPublish();
426  break;
427  }
428  }
429 
430  fit_residual_ = rhs - lhs * fit_soln_;
431  if(odometry_residual_.array().abs().maxCoeff() <= ODOMETRY_THRESHOLD) {
432  ROS_DEBUG("Breaking out since odometry looks good");
433  break;
434  }
435  for(int j = 0; j < base_kin_.num_wheels_; j++) {
436  int fw = 2 * j;
437  int sw = fw + 1;
438  if(fabs(fit_residual_(fw, 0)) > fabs(fit_residual_(sw, 0))) {
439  fit_residual_(fw, 0) = fabs(fit_residual_(fw, 0));
440  fit_residual_(sw, 0) = fit_residual_(fw, 0);
441  } else {
442  fit_residual_(fw, 0) = fabs(fit_residual_(sw, 0));
443  fit_residual_(sw, 0) = fit_residual_(fw, 0);
444  }
445  }
447 
448  }
449  return fit_soln_;
450  }
451 
453  {
454  w_fit.setIdentity();
455  double g_sigma = 0.1;
456 
457  for(int i = 0; i < 2 * base_kin_.num_wheels_; i++) {
458  w_fit(i, i) = sqrt(exp(-pow(residual(i, 0), 2) /
459  (2 * g_sigma * g_sigma) ));
460  }
461  return w_fit;
462  }
463 
465  {
466  if(fabs((last_odometer_publish_time_ - current_time_).toSec()) <
468  return;
469  if(odometer_publisher_->trylock()) {
470  odometer_publisher_->msg_.distance = odometer_distance_;
471  odometer_publisher_->msg_.angle = odometer_angle_;
472  odometer_publisher_->unlockAndPublish();
474  }
475  }
476 
478  {
479  if(fabs((last_state_publish_time_ - current_time_).toSec()) <
481  return;
482  if(state_publisher_->trylock()) {
483  for(int i=0; i < base_kin_.num_wheels_; i++) {
484  state_publisher_->msg_.wheel_link_names[i] =
485  base_kin_.wheel_[i].link_name_;
486 
487  state_publisher_->msg_.drive_constraint_errors[i] =
488  odometry_residual_(2*i,0);
489 
490  state_publisher_->msg_.longitudinal_slip_constraint_errors[i] =
491  odometry_residual_(2*i+1,0);
492  }
493  state_publisher_->msg_.velocity = odom_vel_;
494  state_publisher_->unlockAndPublish();
496  }
497  }
498 
499  void Pr2Odometry::publish()
500  {
501  if(fabs((last_publish_time_ - current_time_).toSec()) <
503  return;
504 
505  if(odometry_publisher_->trylock()) {
507  odometry_publisher_->unlockAndPublish();
509  }
510  }
511 
513  {
514  if(fabs((last_transform_publish_time_ - current_time_).toSec()) <
516  return;
517  if(transform_publisher_->trylock()) {
518  double x(0.), y(0.0), yaw(0.0), vx(0.0), vy(0.0), vyaw(0.0);
519  this->getOdometry(x, y, yaw, vx, vy, vyaw);
520 
521  geometry_msgs::TransformStamped &out =
522  transform_publisher_->msg_.transforms[0];
523 
524  out.header.stamp = current_time_;
525  out.header.frame_id = tf::resolve(tf_prefix_,base_footprint_frame_);
526  out.child_frame_id = tf::resolve(tf_prefix_,odom_frame_);
527  out.transform.translation.x = -x * cos(yaw) - y * sin(yaw);
528  out.transform.translation.y = +x * sin(yaw) - y * cos(yaw);
529  out.transform.translation.z = 0;
530  tf::Quaternion quat_trans;
531  quat_trans.setRPY(0.0, 0.0, -yaw);
532 
533  out.transform.rotation.x = quat_trans.x();
534  out.transform.rotation.y = quat_trans.y();
535  out.transform.rotation.z = quat_trans.z();
536  out.transform.rotation.w = quat_trans.w();
537 
538  transform_publisher_->unlockAndPublish();
540  }
541  }
542 } // namespace
controller::Pr2Odometry::publishTransform
void publishTransform()
Publishes the currently computed odometry information to tf.
Definition: pr2_odometry.cpp:544
controller::Pr2Odometry::cbv_lhs_
OdomMatrix16x3 cbv_lhs_
Definition: pr2_odometry.h:350
controller::Pr2Odometry::transform_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > transform_publisher_
Publishes the transform between the odometry frame and the base frame.
Definition: pr2_odometry.h:318
controller::OdomMatrix16x16
Eigen::Matrix< float, 16, 16 > OdomMatrix16x16
Definition: pr2_odometry.h:92
controller::Pr2Odometry::cov_x_theta_
double cov_x_theta_
Definition: pr2_odometry.h:320
controller::Pr2Odometry::Pr2Odometry
Pr2Odometry()
Constructor for the odometry.
Definition: pr2_odometry.cpp:81
msg
msg
controller::MAX_ALLOWABLE_SVD_TIME
const static double MAX_ALLOWABLE_SVD_TIME
Definition: pr2_odometry.cpp:79
controller::OdomMatrix3x1
Eigen::Matrix< float, 3, 1 > OdomMatrix3x1
Definition: pr2_odometry.h:89
controller::Pr2Odometry::node_
ros::NodeHandle node_
Definition: pr2_odometry.h:158
i
int i
controller::Pr2Odometry::odometry_residual_max_
double odometry_residual_max_
Maximum residual from the iteritive least squares.
Definition: pr2_odometry.h:248
controller::Pr2Odometry::caster_calibration_multiplier_
double caster_calibration_multiplier_
Definition: pr2_odometry.h:348
controller::Pr2Odometry::odometer_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::Odometer > > odometer_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
Definition: pr2_odometry.h:308
controller::Pr2Odometry::last_time_
ros::Time last_time_
Stores the last update time and the current update time.
Definition: pr2_odometry.h:228
controller::Pr2Odometry::tf_prefix_
std::string tf_prefix_
Definition: pr2_odometry.h:356
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
controller::Pr2Odometry::base_kin_
BaseKinematics base_kin_
class where the robot's information is computed and stored
Definition: pr2_odometry.h:163
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
controller::Pr2Odometry::ils_max_iterations_
int ils_max_iterations_
Number of iterations used during iterative least squares.
Definition: pr2_odometry.h:243
controller::Pr2Odometry::verbose_
bool verbose_
Definition: pr2_odometry.h:340
controller::Pr2Odometry::getCorrectedWheelSpeed
double getCorrectedWheelSpeed(const int &index)
Computes the wheel's speed adjusted for the attached caster's rotational velocity.
Definition: pr2_odometry.cpp:412
controller::Pr2Odometry::odometer_publish_rate_
double odometer_publish_rate_
Definition: pr2_odometry.h:344
controller::Pr2Odometry::~Pr2Odometry
~Pr2Odometry()
Destructor for the odometry.
Definition: pr2_odometry.cpp:86
controller::Pr2Odometry::update
void update()
(a) Updates positions of the caster and wheels. Called every timestep in realtime
Definition: pr2_odometry.cpp:221
ROS_DEBUG
#define ROS_DEBUG(...)
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
controller::Pr2Odometry::last_state_publish_time_
ros::Time last_state_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:283
controller::Pr2Odometry::last_transform_publish_time_
ros::Time last_transform_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:273
controller::Pr2Odometry::state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseOdometryState > > state_publisher_
The RealtimePublisher that does the realtime publishing of the odometry state.
Definition: pr2_odometry.h:313
controller::OdomMatrix16x3
Eigen::Matrix< float, 16, 3 > OdomMatrix16x3
Definition: pr2_odometry.h:91
controller::Pr2Odometry::odom_
geometry_msgs::Point odom_
Point that stores the current translational position (x,y) and angular position (z)
Definition: pr2_odometry.h:233
controller::Pr2Odometry::starting
void starting()
Definition: pr2_odometry.cpp:211
controller::BaseKinematics::caster_
std::vector< Caster > caster_
vector of every caster attached to the base
Definition: base_kinematics.h:309
controller::Pr2Odometry::last_odometer_publish_time_
ros::Time last_odometer_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:278
controller::BaseKinematics::wheel_
std::vector< Wheel > wheel_
vector of every wheel attached to the base
Definition: base_kinematics.h:304
controller::Pr2Odometry::publish_tf_
bool publish_tf_
enable or disable tf publishing
Definition: pr2_odometry.h:325
controller::Pr2Odometry::fit_residual_
OdomMatrix16x1 fit_residual_
Definition: pr2_odometry.h:351
controller::Pr2Odometry::odometer_distance_
double odometer_distance_
Total distance traveled by the base as computed by the odometer.
Definition: pr2_odometry.h:218
controller::Pr2Odometry::cov_x_y_
double cov_x_y_
Definition: pr2_odometry.h:320
realtime_tools::RealtimePublisher
controller::Pr2Odometry::cbv_soln_
OdomMatrix3x1 cbv_soln_
Definition: pr2_odometry.h:354
controller::Pr2Odometry::publish_state_
bool publish_state_
Definition: pr2_odometry.h:340
controller::Pr2Odometry::publish_odom_
bool publish_odom_
Definition: pr2_odometry.h:340
controller::Pr2Odometry::debug_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::DebugInfo > > debug_publisher_
Definition: pr2_odometry.h:334
controller::BaseKinematics::num_wheels_
int num_wheels_
number of wheels connected to the base
Definition: base_kinematics.h:294
controller
controller::Pr2Odometry::odom_publish_rate_
double odom_publish_rate_
Definition: pr2_odometry.h:342
controller::Pr2Odometry::odom_vel_
geometry_msgs::Twist odom_vel_
Twist that remembers the current translational velocities (vel.vx, vel.vy) and angular position (ang_...
Definition: pr2_odometry.h:238
pr2_mechanism_model::RobotState
controller::Pr2Odometry::sequence_
int sequence_
Definition: pr2_odometry.h:336
k
int k
controller::BaseKinematics::pointVel2D
geometry_msgs::Twist pointVel2D(const geometry_msgs::Point &pos, const geometry_msgs::Twist &vel)
Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation...
Definition: base_kinematics.cpp:229
controller::Pr2Odometry::current_time_
ros::Time current_time_
Definition: pr2_odometry.h:228
controller::Pr2Odometry
Definition: pr2_odometry.h:98
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
ROS_ERROR
#define ROS_ERROR(...)
controller::Pr2Odometry::state_publish_rate_
double state_publish_rate_
Definition: pr2_odometry.h:346
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
controller::Pr2Odometry::w_fit
OdomMatrix16x16 w_fit
Definition: pr2_odometry.h:353
controller::Pr2Odometry::findWeightMatrix
OdomMatrix16x16 findWeightMatrix(const OdomMatrix16x1 &residual)
Finds the weight matrix from the iterative least squares residuals.
Definition: pr2_odometry.cpp:484
controller::Pr2Odometry::publishOdometer
void publishOdometer()
Publishes the currently computed odometer information.
Definition: pr2_odometry.cpp:496
controller::ODOMETRY_THRESHOLD
const static double ODOMETRY_THRESHOLD
Definition: pr2_odometry.cpp:78
controller::Pr2Odometry::publish_odometer_
bool publish_odometer_
Definition: pr2_odometry.h:340
controller::Pr2Odometry::base_footprint_frame_
std::string base_footprint_frame_
The topic name of the base footprint frame.
Definition: pr2_odometry.h:263
pr2_controller_interface::Controller
controller::Pr2Odometry::expected_odometer_publish_time_
double expected_odometer_publish_time_
The time that the odometry is expected to be published next.
Definition: pr2_odometry.h:293
controller::Pr2Odometry::odometry_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odometry_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
Definition: pr2_odometry.h:303
controller::Pr2Odometry::populateCovariance
void populateCovariance(const double &residual, nav_msgs::Odometry &msg)
populate the covariance part of the odometry message
Definition: pr2_odometry.cpp:316
controller::Pr2Odometry::cov_y_theta_
double cov_y_theta_
Definition: pr2_odometry.h:320
controller::Pr2Odometry::odometry_residual_
OdomMatrix16x1 odometry_residual_
Definition: pr2_odometry.h:351
controller::Pr2Odometry::expected_state_publish_time_
double expected_state_publish_time_
The time that the odometry is expected to be published next.
Definition: pr2_odometry.h:298
controller::BaseKinematics::robot_state_
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
Definition: base_kinematics.h:289
controller::OdomMatrix16x1
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
Definition: pr2_odometry.h:90
pr2_mechanism_model::RobotState::getTime
ros::Time getTime()
ros::Time
controller::Pr2Odometry::computeBaseVelocity
void computeBaseVelocity()
Computes the base velocity from the caster positions and wheel speeds.
Definition: pr2_odometry.cpp:372
controller::Pr2Odometry::isInputValid
bool isInputValid()
Definition: pr2_odometry.cpp:194
controller::Pr2Odometry::last_publish_time_
ros::Time last_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:268
controller::Pr2Odometry::weight_matrix_
OdomMatrix16x16 weight_matrix_
Definition: pr2_odometry.h:353
controller::Pr2Odometry::init
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Initializes and loads odometry information from the param server.
Definition: pr2_odometry.cpp:90
class_list_macros.hpp
controller::Pr2Odometry::expected_publish_time_
double expected_publish_time_
The time that the odometry is expected to be published next.
Definition: pr2_odometry.h:288
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
controller::Pr2Odometry::fit_soln_
OdomMatrix3x1 fit_soln_
Definition: pr2_odometry.h:354
controller::Pr2Odometry::fit_lhs_
OdomMatrix16x3 fit_lhs_
Definition: pr2_odometry.h:350
controller::Pr2Odometry::getOdometry
void getOdometry(double &x, double &y, double &yaw, double &vx, double &vy, double &vw)
Takes the current odometery information and stores it into the six double parameters.
Definition: pr2_odometry.cpp:361
controller::BaseKinematics::init
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server.
Definition: base_kinematics.cpp:158
controller::Pr2Odometry::publish
void publish()
Publishes the currently computed odometry information.
Definition: pr2_odometry.cpp:531
controller::Pr2Odometry::fit_rhs_
OdomMatrix16x1 fit_rhs_
Definition: pr2_odometry.h:352
controller::Pr2Odometry::base_link_frame_
std::string base_link_frame_
The topic name of the base link frame.
Definition: pr2_odometry.h:258
controller::Pr2Odometry::sigma_y_
double sigma_y_
Definition: pr2_odometry.h:320
controller::Pr2Odometry::sigma_theta_
double sigma_theta_
Definition: pr2_odometry.h:320
controller::Pr2Odometry::matrix_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::OdometryMatrix > > matrix_publisher_
Definition: pr2_odometry.h:333
controller::BaseKinematics::num_casters_
int num_casters_
number of casters connected to the base
Definition: base_kinematics.h:299
tf::Quaternion
controller::Pr2Odometry::cbv_rhs_
OdomMatrix16x1 cbv_rhs_
Definition: pr2_odometry.h:351
controller::Pr2Odometry::odometer_angle_
double odometer_angle_
Total angular distance traveled by the base as computed by the odometer.
Definition: pr2_odometry.h:223
pr2_odometry.h
ros::NodeHandle
controller::Pr2Odometry::getOdometryMessage
void getOdometryMessage(nav_msgs::Odometry &msg)
Builds the odometry message and prepares it for sending.
Definition: pr2_odometry.cpp:297
controller::Pr2Odometry::publishState
void publishState()
Publishes the odometry state information.
Definition: pr2_odometry.cpp:509
controller::Pr2Odometry::iterativeLeastSquares
OdomMatrix3x1 iterativeLeastSquares(const OdomMatrix16x3 &lhs, const OdomMatrix16x1 &rhs, const int &max_iter)
Function used to compute the most likely solution to the odometry using iterative least squares.
Definition: pr2_odometry.cpp:424
ros::Time::now
static Time now()
controller::Pr2Odometry::updateOdometry
void updateOdometry()
Finds and stores the latest odometry information.
Definition: pr2_odometry.cpp:263
controller::Pr2Odometry::sigma_x_
double sigma_x_
Definition: pr2_odometry.h:320
controller::Pr2Odometry::odom_frame_
std::string odom_frame_
The topic name of the published odometry.
Definition: pr2_odometry.h:253


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:33:25