49 Pr2Odometry::Pr2Odometry()
54 Pr2Odometry::~Pr2Odometry()
62 std::string prefix_param;
64 node.
getParam(prefix_param, tf_prefix_);
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);
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_,
77 node.
param<std::string> (
"base_link_frame", base_link_frame_,
"base_link");
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);
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);
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",
92 caster_calibration_multiplier_, 1.0);
94 if(odom_publish_rate_ <= 0.0) {
95 expected_publish_time_ = 0.0;
96 publish_odom_ =
false;
98 expected_publish_time_ = 1.0/odom_publish_rate_;
102 if(odometer_publish_rate_ <= 0.0) {
103 expected_odometer_publish_time_ = 0.0;
104 publish_odometer_ =
false;
106 expected_odometer_publish_time_ = 1.0/odometer_publish_rate_;
107 publish_odometer_ =
true;
110 if(state_publish_rate_ <= 0.0) {
111 expected_state_publish_time_ = 0.0;
112 publish_state_ =
false;
114 expected_state_publish_time_ = 1.0/state_publish_rate_;
115 publish_state_ =
true;
120 if(!base_kin_.init(robot_state, node_))
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.");
138 fit_residual_.setZero();
139 odometry_residual_.setZero();
140 weight_matrix_.setIdentity();
145 debug_publisher_->msg_.timing.resize(3);
146 matrix_publisher_->msg_.m.resize(48);
154 transform_publisher_->msg_.transforms.resize(1);
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_);
162 bool Pr2Odometry::isInputValid()
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_))
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_))
179 void Pr2Odometry::starting()
181 current_time_ = base_kin_.robot_state_->getTime();
182 last_time_ = base_kin_.robot_state_->getTime();
183 last_publish_time_ = base_kin_.robot_state_->getTime();
184 last_transform_publish_time_ = base_kin_.robot_state_->getTime();
185 last_state_publish_time_ = base_kin_.robot_state_->getTime();
186 last_odometer_publish_time_ = base_kin_.robot_state_->getTime();
189 void Pr2Odometry::update()
191 if(!isInputValid()) {
193 debug_publisher_->msg_.input_valid =
false;
194 ROS_DEBUG(
"Odometry:: Input velocities are invalid");
199 debug_publisher_->msg_.input_valid =
true;
202 current_time_ = base_kin_.robot_state_->getTime();
210 if(publish_odometer_)
219 debug_publisher_->msg_.timing[0] = update_time;
220 debug_publisher_->msg_.timing[1] = publish_time;
221 debug_publisher_->msg_.residual = odometry_residual_max_;
222 debug_publisher_->msg_.sequence = sequence_;
223 if(debug_publisher_->trylock()) {
224 debug_publisher_->unlockAndPublish();
227 last_time_ = current_time_;
231 void Pr2Odometry::updateOdometry()
233 double dt = (current_time_ - last_time_).toSec();
234 double theta = odom_.z;
235 double costh =
cos(theta);
236 double sinth =
sin(theta);
238 computeBaseVelocity();
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;
246 odom_.x += odom_delta_x;
247 odom_.y += odom_delta_y;
248 odom_.z += odom_delta_th;
250 ROS_DEBUG(
"Odometry:: Position: %f, %f, %f",odom_.x,odom_.y,odom_.z);
252 odometer_distance_ +=
sqrt(odom_delta_x * odom_delta_x +
253 odom_delta_y * odom_delta_y);
254 odometer_angle_ += fabs(odom_delta_th);
257 void Pr2Odometry::getOdometry(geometry_msgs::Point &odom,
258 geometry_msgs::Twist &odom_vel)
261 odom_vel = odom_vel_;
265 void Pr2Odometry::getOdometryMessage(nav_msgs::Odometry &msg)
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;
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();
280 msg.twist.twist = odom_vel_;
281 populateCovariance(odometry_residual_max_,msg);
284 void Pr2Odometry::populateCovariance(
const double &residual,
285 nav_msgs::Odometry &msg)
287 double odom_multiplier = 1.0;
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) {
293 msg.pose.covariance[0] = 1e-12;
294 msg.pose.covariance[7] = 1e-12;
295 msg.pose.covariance[35] = 1e-12;
297 msg.pose.covariance[1] = 1e-12;
298 msg.pose.covariance[6] = 1e-12;
300 msg.pose.covariance[31] = 1e-12;
301 msg.pose.covariance[11] = 1e-12;
303 msg.pose.covariance[30] = 1e-12;
304 msg.pose.covariance[5] = 1e-12;
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);
311 msg.pose.covariance[1] = odom_multiplier*cov_x_y_;
312 msg.pose.covariance[6] = odom_multiplier*cov_x_y_;
314 msg.pose.covariance[31] = odom_multiplier*cov_y_theta_;
315 msg.pose.covariance[11] = odom_multiplier*cov_y_theta_;
317 msg.pose.covariance[30] = odom_multiplier*cov_x_theta_;
318 msg.pose.covariance[5] = odom_multiplier*cov_x_theta_;
321 msg.pose.covariance[14] = DBL_MAX;
322 msg.pose.covariance[21] = DBL_MAX;
323 msg.pose.covariance[28] = DBL_MAX;
325 msg.twist.covariance = msg.pose.covariance;
329 void Pr2Odometry::getOdometry(
double &x,
double &y,
double &yaw,
330 double &vx,
double &vy,
double &vw)
335 vx = odom_vel_.linear.x;
336 vy = odom_vel_.linear.y;
337 vw = odom_vel_.angular.z;
340 void Pr2Odometry::computeBaseVelocity()
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_;
349 wheel_position = base_kin_.wheel_[i].position_;
350 costh =
cos(steer_angle);
351 sinth =
sin(steer_angle);
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;
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;
368 cbv_soln_ = iterativeLeastSquares(cbv_lhs_, cbv_rhs_, ils_max_iterations_);
370 odometry_residual_ = cbv_lhs_ * cbv_soln_ - cbv_rhs_;
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);
380 double Pr2Odometry::getCorrectedWheelSpeed(
const int &index)
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_);
395 weight_matrix_.setIdentity();
396 double svd_time = 0.0;
397 bool pub_matrix =
false;
400 for(
int i = 0; i < max_iter; i++) {
401 fit_lhs_ = weight_matrix_ * lhs;
402 fit_rhs_ = weight_matrix_ * rhs;
406 Eigen::JacobiSVD<Eigen::MatrixXf> svdOfFit(fit_lhs_,Eigen::ComputeThinU|Eigen::ComputeThinV);
407 fit_soln_ = svdOfFit.solve(fit_rhs_);
409 ROS_DEBUG(
"Odometry:: fit_soln_: %f %f %f",
410 fit_soln_(0,0), fit_soln_(1,0), fit_soln_(2,0));
414 debug_publisher_->msg_.timing[2] = svd_time;
415 if(svd_time > MAX_ALLOWABLE_SVD_TIME) {
416 for(
int k = 0; k < 48; k++) {
418 int j_index = k - i_index *3;
419 matrix_publisher_->msg_.m[i] = fit_lhs_(i_index,j_index);
424 if(matrix_publisher_->trylock())
425 matrix_publisher_->unlockAndPublish();
430 fit_residual_ = rhs - lhs * fit_soln_;
432 ROS_DEBUG(
"Breaking out since odometry looks good");
435 for(
int j = 0; j < base_kin_.num_wheels_; j++) {
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);
442 fit_residual_(fw, 0) = fabs(fit_residual_(sw, 0));
443 fit_residual_(sw, 0) = fit_residual_(fw, 0);
446 weight_matrix_ = findWeightMatrix(fit_residual_);
455 double g_sigma = 0.1;
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) ));
464 void Pr2Odometry::publishOdometer()
466 if(fabs((last_odometer_publish_time_ - current_time_).toSec()) <
467 expected_odometer_publish_time_)
469 if(odometer_publisher_->trylock()) {
470 odometer_publisher_->msg_.distance = odometer_distance_;
471 odometer_publisher_->msg_.angle = odometer_angle_;
472 odometer_publisher_->unlockAndPublish();
473 last_odometer_publish_time_ = current_time_;
477 void Pr2Odometry::publishState()
479 if(fabs((last_state_publish_time_ - current_time_).toSec()) <
480 expected_state_publish_time_)
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_;
487 state_publisher_->msg_.drive_constraint_errors[i] =
488 odometry_residual_(2*i,0);
490 state_publisher_->msg_.longitudinal_slip_constraint_errors[i] =
491 odometry_residual_(2*i+1,0);
493 state_publisher_->msg_.velocity = odom_vel_;
494 state_publisher_->unlockAndPublish();
495 last_state_publish_time_ = current_time_;
499 void Pr2Odometry::publish()
501 if(fabs((last_publish_time_ - current_time_).toSec()) <
502 expected_publish_time_)
505 if(odometry_publisher_->trylock()) {
506 getOdometryMessage(odometry_publisher_->msg_);
507 odometry_publisher_->unlockAndPublish();
508 last_publish_time_ = current_time_;
512 void Pr2Odometry::publishTransform()
514 if(fabs((last_transform_publish_time_ - current_time_).toSec()) <
515 expected_publish_time_)
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);
521 geometry_msgs::TransformStamped &out =
522 transform_publisher_->msg_.transforms[0];
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;
531 quat_trans.
setRPY(0.0, 0.0, -yaw);
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();
538 transform_publisher_->unlockAndPublish();
539 last_transform_publish_time_ = current_time_;
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
Eigen::Matrix< float, 3, 1 > OdomMatrix3x1
static const double MAX_ALLOWABLE_SVD_TIME
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string resolve(const std::string &prefix, const std::string &frame_name)
static const double ODOMETRY_THRESHOLD
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
Eigen::Matrix< float, 16, 16 > OdomMatrix16x16
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
bool getParam(const std::string &key, std::string &s) const
Eigen::Matrix< float, 16, 3 > OdomMatrix16x3
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)