36 #include <jsk_topic_tools/rosparam_utils.h>
38 #include <std_msgs/String.h>
41 #include <kdl/chainfksolverpos_recursive.hpp>
42 #include <kdl/chainfksolvervel_recursive.hpp>
44 #include <geometry_msgs/TwistStamped.h>
46 #include <boost/assign/list_of.hpp>
56 odom_status_ = UNINITIALIZED;
57 odom_pose_ = Eigen::Affine3d::Identity();
59 root_link_pose_.setIdentity();
62 diagnostic_updater_->setHardwareID(
"none");
63 diagnostic_updater_->add(
"Support Leg Status",
this,
64 &Footcoords::updateLegDiagnostics);
67 pnh.param(
"alpha", alpha_, 0.1);
68 pnh.param(
"sampling_time_", sampling_time_, 0.2);
69 pnh.param(
"output_frame_id", output_frame_id_,
70 std::string(
"odom_on_ground"));
71 pnh.param(
"zmp_frame_id", zmp_frame_id_,
74 pnh.param(
"parent_frame_id", parent_frame_id_, std::string(
"odom"));
75 pnh.param(
"midcoords_frame_id", midcoords_frame_id_, std::string(
"ground"));
76 pnh.param(
"root_frame_id", root_frame_id_, std::string(
"BODY"));
77 pnh.param(
"body_on_odom_frame", body_on_odom_frame_, std::string(
"body_on_odom"));
78 pnh.param(
"odom_init_frame_id", odom_init_frame_id_, std::string(
"odom_init"));
79 pnh.param(
"invert_odom_init", invert_odom_init_,
true);
80 pnh.param(
"lfoot_frame_id", lfoot_frame_id_,
81 std::string(
"lleg_end_coords"));
82 pnh.param(
"rfoot_frame_id", rfoot_frame_id_,
83 std::string(
"rleg_end_coords"));
84 pnh.param(
"publish_odom_tf", publish_odom_tf_,
true);
89 ROS_FATAL(
"Failed to load robot_description");
93 tree.getChain(root_frame_id_, lfoot_frame_id_, lfoot_chain_);
94 tree.getChain(root_frame_id_, rfoot_frame_id_, rfoot_chain_);
95 for (
size_t i=0;
i < lfoot_chain_.getNrOfSegments();
i++){
97 << lfoot_chain_.getSegment(i).getJoint().getName().c_str());
99 for (
size_t i=0;
i < rfoot_chain_.getNrOfSegments();
i++){
101 << rfoot_chain_.getSegment(i).getJoint().getName().c_str());
103 pnh.param(
"lfoot_sensor_frame", lfoot_sensor_frame_, std::string(
"lleg_end_coords"));
104 pnh.param(
"rfoot_sensor_frame", rfoot_sensor_frame_, std::string(
"rleg_end_coords"));
107 pnh.param(
"force_threshold", force_thr_, 200.0);
108 support_status_ = AIR;
109 pub_low_level_ = pnh.advertise<jsk_footstep_controller::FootCoordsLowLevelInfo>(
"low_level_info", 1);
110 pub_state_ = pnh.advertise<std_msgs::String>(
"state", 1);
111 pub_contact_state_ = pnh.advertise<jsk_footstep_controller::GroundContactState>(
"contact_state", 1);
112 pub_synchronized_forces_ = pnh.advertise<jsk_footstep_controller::SynchronizedForces>(
"synchronized_forces", 1);
113 pub_debug_lfoot_pos_ = pnh.advertise<geometry_msgs::Pose>(
"debug/lfoot_pose", 1);
114 pub_debug_rfoot_pos_ = pnh.advertise<geometry_msgs::Pose>(
"debug/rfoot_pose", 1);
115 pub_leg_odometory_ = pnh.advertise<geometry_msgs::PoseStamped>(
"leg_odometry", 1);
116 pub_twist_ = pnh.advertise<geometry_msgs::TwistStamped>(
"base_vel", 1);
117 pub_odom_init_transform_ = pnh.advertise<geometry_msgs::TransformStamped>(
"odom_init_transform", 1,
true);
118 pub_odom_init_pose_stamped_ = pnh.advertise<geometry_msgs::PoseStamped>(
"odom_init_pose_stamped", 1,
true);
119 before_on_the_air_ =
true;
120 pnh.param(
"use_imu", use_imu_,
false);
121 pnh.param(
"use_imu_yaw", use_imu_yaw_,
true);
122 if (publish_odom_tf_) {
123 odom_sub_.subscribe(pnh,
"/odom", 50);
124 imu_sub_.subscribe(pnh,
"/imu", 50);
125 odom_imu_sync_ = boost::make_shared<message_filters::Synchronizer<OdomImuSyncPolicy> >(100);
126 odom_imu_sync_->connectInput(odom_sub_, imu_sub_);
127 odom_imu_sync_->registerCallback(boost::bind(&Footcoords::odomImuCallback,
this, _1, _2));
129 odom_init_pose_ = Eigen::Affine3d::Identity();
130 odom_init_trigger_sub_ = pnh.subscribe(
"/odom_init_trigger", 1,
131 &Footcoords::odomInitTriggerCallback,
this);
132 periodic_update_timer_ = pnh.createTimer(
ros::Duration(1.0 / 25),
133 boost::bind(&Footcoords::periodicTimerCallback,
this, _1));
134 sub_lfoot_force_.subscribe(nh,
"lfsensor", 50);
135 sub_rfoot_force_.subscribe(nh,
"rfsensor", 50);
136 sub_joint_states_.subscribe(nh,
"joint_states",50);
137 sub_zmp_.subscribe(nh,
"zmp", 50);
138 floor_coeffs_sub_ = pnh.subscribe(
"/floor_coeffs", 1,
139 &Footcoords::floorCoeffsCallback,
this);
142 std::vector<float> temp = boost::assign::list_of(0)(0)(1)(0);
143 floor_coeffs_ = temp;
144 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
145 sync_->connectInput(sub_lfoot_force_, sub_rfoot_force_, sub_joint_states_, sub_zmp_);
146 sync_->registerCallback(boost::bind(&Footcoords::synchronizeForces,
this, _1, _2, _3, _4));
147 synchronized_forces_sub_ = pnh.subscribe(
"synchronized_forces", 20,
148 &Footcoords::filter,
this);
151 Footcoords::~Footcoords()
160 if (support_status_ == AIR) {
161 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"On Air");
164 if (support_status_ == LLEG_GROUND) {
165 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Left leg on the ground");
167 else if (support_status_ == RLEG_GROUND) {
168 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Right leg on the ground");
170 else if (support_status_ == BOTH_GROUND) {
171 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Both legs on the ground");
176 double Footcoords::applyLowPassFilter(
double current_val,
double prev_val)
const
178 return prev_val + alpha_ * (current_val - prev_val);
181 bool Footcoords::allValueLargerThan(TimeStampedVector<ValueStamped::Ptr>& values,
184 for (
size_t i = 0;
i <
values.size();
i++) {
192 bool Footcoords::allValueSmallerThan(TimeStampedVector<ValueStamped::Ptr>& values,
195 for (
size_t i = 0;
i <
values.size();
i++) {
203 bool Footcoords::resolveForceTf(
const geometry_msgs::WrenchStamped& lfoot,
204 const geometry_msgs::WrenchStamped& rfoot,
205 tf::Vector3& lfoot_force,
206 tf::Vector3& rfoot_force)
209 if (!waitForSensorFrameTransformation(lfoot.header.stamp, rfoot.header.stamp, lfoot.header.frame_id, rfoot.header.frame_id)) {
210 ROS_ERROR(
"[Footcoords::resolveForceTf] failed to lookup transformation for sensor value");
214 tf_listener_->lookupTransform(
215 lfoot.header.frame_id, lfoot_sensor_frame_, lfoot.header.stamp, lfoot_transform);
216 tf_listener_->lookupTransform(
217 rfoot.header.frame_id, rfoot_sensor_frame_, rfoot.header.stamp, rfoot_transform);
219 lfoot_transform.
setOrigin(tf::Vector3(0, 0, 0));
220 rfoot_transform.
setOrigin(tf::Vector3(0, 0, 0));
222 tf::Vector3 lfoot_local, rfoot_local;
225 lfoot_force = lfoot_transform * lfoot_local;
226 rfoot_force = rfoot_transform * rfoot_local;
232 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
236 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
240 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
244 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
251 boost::mutex::scoped_lock
lock(mutex_);
252 bool success_to_update = computeMidCoords(event.
current_real);
253 if (support_status_ == AIR || support_status_ == BOTH_GROUND) {
254 publishState(
"ground");
257 if (support_status_ == LLEG_GROUND) {
258 publishState(
"lfoot");
260 else if (support_status_ == RLEG_GROUND) {
261 publishState(
"rfoot");
272 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
275 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
278 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
281 ROS_ERROR(
"[Footcoords::resolveForceTf] transform error: %s", e.what());
292 ground_transform_ = midcoords_;
294 diagnostic_updater_->update();
298 void Footcoords::synchronizeForces(
const geometry_msgs::WrenchStamped::ConstPtr& lfoot,
299 const geometry_msgs::WrenchStamped::ConstPtr& rfoot,
300 const sensor_msgs::JointState::ConstPtr& joint_states,
301 const geometry_msgs::PointStamped::ConstPtr& zmp)
303 jsk_footstep_controller::SynchronizedForces forces;
304 forces.header = lfoot->header;
305 forces.lleg_force = *lfoot;
306 forces.rleg_force = *rfoot;
309 pub_synchronized_forces_.publish(forces);
310 Eigen::Vector3d zmp_point;
313 if (zmp->point.z < 0) {
314 geometry_msgs::TransformStamped ros_zmp_coords;
315 ros_zmp_coords.header = zmp->header;
316 ros_zmp_coords.child_frame_id = zmp_frame_id_;
317 Eigen::Affine3d zmp_pose = Eigen::Affine3d::Identity() * Eigen::Translation3d(zmp_point);
319 std::vector<geometry_msgs::TransformStamped> tf_transforms;
320 tf_transforms.push_back(ros_zmp_coords);
322 boost::mutex::scoped_lock
lock(mutex_);
323 tf_broadcaster_.sendTransform(tf_transforms);
328 void Footcoords::updateChain(std::map<std::string, double>& joint_angles,
332 KDL::JntArray jnt_pos(chain.getNrOfJoints());
333 for (
int i = 0, j = 0;
i < chain.getNrOfSegments();
i++) {
338 std::string joint_name = chain.getSegment(
i).getJoint().getName();
339 if (joint_angles.find(joint_name) != joint_angles.end()) {
340 jnt_pos(j++) = joint_angles[joint_name];
343 KDL::ChainFkSolverPos_recursive fk_solver(chain);
345 if (fk_solver.JntToCart(jnt_pos,
pose) < 0) {
351 void Footcoords::updateRobotModel(std::map<std::string, double>& joint_angles)
354 updateChain(joint_angles, lfoot_chain_, lfoot_pose_);
355 updateChain(joint_angles, rfoot_chain_, rfoot_pose_);
356 geometry_msgs::Pose ros_lfoot_pose, ros_rfoot_pose;
359 pub_debug_lfoot_pos_.publish(ros_lfoot_pose);
360 pub_debug_rfoot_pos_.publish(ros_rfoot_pose);
363 void Footcoords::computeVelicity(
double dt,
364 std::map<std::string, double>& joint_angles,
366 geometry_msgs::Twist& output)
368 KDL::ChainFkSolverVel_recursive fk_solver(chain);
369 KDL::JntArrayVel jnt_pos(chain.getNrOfJoints());
370 KDL::JntArray
q(chain.getNrOfJoints()), qdot(chain.getNrOfJoints());
371 for (
int i = 0, j = 0;
i < chain.getNrOfSegments();
i++) {
372 std::string joint_name = chain.getSegment(
i).getJoint().getName();
373 if (joint_angles.find(joint_name) != joint_angles.end()) {
374 qdot(j) = (joint_angles[joint_name] - prev_joints_[joint_name]) / dt;
375 q(j++) = joint_angles[joint_name];
381 if (fk_solver.JntToCart(jnt_pos, vel) < 0) {
384 KDL::Twist twist = vel.GetTwist();
388 void Footcoords::estimateVelocity(
const ros::Time& stamp, std::map<std::string, double>& joint_angles)
390 geometry_msgs::TwistStamped twist_stamped;
391 if (!prev_joints_.empty()) {
392 double dt = (
stamp - last_time_).toSec();
393 if (odom_status_ == LLEG_SUPPORT || odom_status_ == INITIALIZING) {
394 computeVelicity(dt, joint_angles, lfoot_chain_, twist_stamped.twist);
396 else if (odom_status_ == RLEG_SUPPORT) {
397 computeVelicity(dt, joint_angles, rfoot_chain_, twist_stamped.twist);
399 twist_stamped.header.stamp =
stamp;
400 twist_stamped.header.frame_id = root_frame_id_;
401 pub_twist_.publish(twist_stamped);
405 void Footcoords::filter(
const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg)
407 boost::mutex::scoped_lock
lock(mutex_);
408 geometry_msgs::WrenchStamped lfoot =
msg->lleg_force;
409 geometry_msgs::WrenchStamped rfoot =
msg->rleg_force;
410 zmp_ = Eigen::Vector3f(
msg->zmp.point.x,
msg->zmp.point.y,
msg->zmp.point.z);
411 sensor_msgs::JointState joint_angles =
msg->joint_angles;
412 std::map<std::string, double>
angles;
413 for (
size_t i = 0;
i < joint_angles.name.size();
i++) {
414 angles[joint_angles.name[
i]] = joint_angles.position[
i];
420 tf::Vector3 lfoot_force_vector, rfoot_force_vector;
421 if (!resolveForceTf(lfoot, rfoot, lfoot_force_vector, rfoot_force_vector)) {
422 ROS_ERROR(
"[Footcoords::filter] failed to resolve tf of force sensor");
426 double lfoot_force = applyLowPassFilter(lfoot_force_vector[2], prev_lforce_);
427 double rfoot_force = applyLowPassFilter(rfoot_force_vector[2], prev_rforce_);
430 FootCoordsLowLevelInfo
info;
431 info.header = lfoot.header;
432 info.raw_lleg_force = lfoot_force_vector[2];
433 info.raw_rleg_force = rfoot_force_vector[2];
434 info.filtered_lleg_force = lfoot_force;
435 info.filtered_rleg_force = rfoot_force;
436 info.threshold = force_thr_;
437 pub_low_level_.publish(info);
438 prev_lforce_ = lfoot_force;
439 prev_rforce_ = rfoot_force;
441 if (lfoot_force >= force_thr_ && rfoot_force >= force_thr_) {
442 support_status_ = BOTH_GROUND;
444 else if (lfoot_force < force_thr_ && rfoot_force < force_thr_) {
445 support_status_ = AIR;
447 else if (lfoot_force >= force_thr_) {
449 support_status_ = LLEG_GROUND;
451 else if (rfoot_force >= force_thr_) {
453 support_status_ = RLEG_GROUND;
456 estimateVelocity(
msg->header.stamp,
angles);
457 geometry_msgs::PoseStamped leg_odometory;
458 leg_odometory.header.stamp =
msg->header.stamp;
459 leg_odometory.header.frame_id = root_frame_id_;
461 pub_leg_odometory_.publish(leg_odometory);
463 std::vector<geometry_msgs::TransformStamped> tf_transforms;
464 geometry_msgs::TransformStamped odom_transform;
466 odom_transform.header = leg_odometory.header;
467 odom_transform.child_frame_id =
"leg_odom";
468 tf_transforms.push_back(odom_transform);
469 tf_broadcaster_.sendTransform(tf_transforms);
471 last_time_ =
msg->header.stamp;
474 void Footcoords::estimateOdometry()
477 estimateOdometryZMPSupportLeg();
480 void Footcoords::estimateOdometryNaive()
482 if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
483 ROS_INFO(
"changed to INITIALIZING");
484 odom_status_ = INITIALIZING;
486 if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
489 tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().
slerp(rfoot_pose_.getRotation(), 0.5);
490 tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
494 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
495 rfoot_to_origin_pose_ = rfoot_pose_.
inverse() * midcoords;
496 estimated_odom_pose_ = midcoords;
498 if (odom_status_ == INITIALIZING && support_status_ ==RLEG_GROUND) {
500 odom_status_ = RLEG_SUPPORT;
501 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
503 else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
505 odom_status_ = LLEG_SUPPORT;
506 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
508 else if (odom_status_ == RLEG_SUPPORT && support_status_ == RLEG_GROUND) {
510 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
512 else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
514 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
515 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
517 else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
519 odom_status_ = LLEG_SUPPORT;
520 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
522 else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
524 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
526 else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
528 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
529 rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
531 else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
533 odom_status_ = RLEG_SUPPORT;
534 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
536 if (support_status_ == AIR) {
538 odom_status_ = UNINITIALIZED;
542 void Footcoords::estimateOdometryMainSupportLeg()
544 if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
545 ROS_INFO(
"changed to INITIALIZING");
546 odom_status_ = INITIALIZING;
548 if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
551 tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().
slerp(rfoot_pose_.getRotation(), 0.5);
552 tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
556 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
557 rfoot_to_origin_pose_ = rfoot_pose_.
inverse() * midcoords;
558 estimated_odom_pose_ = midcoords;
560 if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
562 odom_status_ = RLEG_SUPPORT;
563 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
565 else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
567 odom_status_ = LLEG_SUPPORT;
568 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
570 else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
572 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
574 else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
575 if (prev_lforce_ > prev_rforce_) {
577 odom_status_ = LLEG_SUPPORT;
579 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
580 rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
584 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
585 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
588 else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
590 odom_status_ = LLEG_SUPPORT;
591 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
593 else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
595 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
597 else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
598 if (prev_rforce_ > prev_lforce_) {
599 odom_status_ = RLEG_SUPPORT;
601 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
602 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
606 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
607 rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
610 else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
612 odom_status_ = RLEG_SUPPORT;
613 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
615 if (support_status_ == AIR) {
617 odom_status_ = UNINITIALIZED;
621 void Footcoords::estimateOdometryZMPSupportLeg()
623 if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
624 ROS_INFO(
"changed to INITIALIZING");
625 odom_status_ = INITIALIZING;
627 if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
630 tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().
slerp(rfoot_pose_.getRotation(), 0.5);
631 tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
635 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
636 rfoot_to_origin_pose_ = rfoot_pose_.
inverse() * midcoords;
637 estimated_odom_pose_ = midcoords;
639 if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
641 odom_status_ = RLEG_SUPPORT;
642 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
644 else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
646 odom_status_ = LLEG_SUPPORT;
647 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
649 else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
651 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
653 else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
656 odom_status_ = LLEG_SUPPORT;
658 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
659 rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
663 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
664 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
667 else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
669 odom_status_ = LLEG_SUPPORT;
670 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
672 else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
674 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
676 else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
678 odom_status_ = RLEG_SUPPORT;
680 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
681 lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
685 estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
686 rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
689 else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
691 odom_status_ = RLEG_SUPPORT;
692 estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
694 if (support_status_ == AIR) {
696 odom_status_ = UNINITIALIZED;
702 void Footcoords::publishState(
const std::string& state)
704 std_msgs::String state_msg;
705 state_msg.data =
state;
706 pub_state_.publish(state_msg);
709 void Footcoords::publishContactState(
const ros::Time& stamp)
711 GroundContactState contact_state;
712 contact_state.header.stamp =
stamp;
713 if (support_status_ == AIR) {
714 contact_state.contact_state
715 = GroundContactState::CONTACT_AIR;
717 else if (support_status_ == LLEG_GROUND) {
718 contact_state.contact_state
719 = GroundContactState::CONTACT_LLEG_GROUND;
721 else if (support_status_ == RLEG_GROUND) {
722 contact_state.contact_state
723 = GroundContactState::CONTACT_RLEG_GROUND;
725 else if (support_status_ == BOTH_GROUND) {
726 contact_state.contact_state
727 = GroundContactState::CONTACT_BOTH_GROUND;
732 tf_listener_->lookupTransform(
733 lfoot_frame_id_, rfoot_frame_id_, stamp, foot_transform);
734 double roll, pitch, yaw;
736 contact_state.error_pitch_angle = std::abs(pitch);
737 contact_state.error_roll_angle = std::abs(roll);
738 contact_state.error_yaw_angle = std::abs(yaw);
739 contact_state.error_z = std::abs(foot_transform.
getOrigin().z());
740 pub_contact_state_.publish(contact_state);
744 ROS_ERROR(
"[Footcoords::publishContactState] transform error: %s", e.what());
748 ROS_ERROR(
"[Footcoords::publishContactState] transform error: %s", e.what());
752 ROS_ERROR(
"[Footcoords::publishContactState] transform error: %s", e.what());
756 ROS_ERROR(
"[Footcoords::publishContactState] transform error: %s", e.what());
761 bool Footcoords::computeMidCoordsFromSingleLeg(
const ros::Time& stamp,
764 if (!waitForEndEffectorTransformation(stamp)) {
765 ROS_ERROR(
"[Footcoords::computeMidCoordsFromSingleLeg] Failed to lookup endeffector transformation");
773 tf_listener_->lookupTransform(
774 root_frame_id_, lfoot_frame_id_, stamp, foot_transform);
777 tf_listener_->lookupTransform(
778 root_frame_id_, rfoot_frame_id_, stamp, foot_transform);
780 midcoords_ = foot_transform.
inverse();
785 ROS_ERROR(
"[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
790 ROS_ERROR(
"[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
795 ROS_ERROR(
"[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
799 ROS_ERROR(
"[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
806 bool Footcoords::computeMidCoords(
const ros::Time& stamp)
808 if (!waitForEndEffectorTransformation(stamp)) {
809 ROS_ERROR(
"[Footcoords::computeMidCoords] Failed to lookup endeffector transformation");
816 tf_listener_->lookupTransform(
817 root_frame_id_, lfoot_frame_id_, stamp, lfoot_transform);
819 tf_listener_->lookupTransform(
820 root_frame_id_, rfoot_frame_id_, stamp, rfoot_transform);
824 tf::Vector3 lfoot_pos = lfoot_transform.
getOrigin();
825 tf::Vector3 rfoot_pos = rfoot_transform.
getOrigin();
826 tf::Vector3 mid_pos = lfoot_pos.lerp(rfoot_pos, 0.5);
827 midcoords_.setOrigin(mid_pos);
828 midcoords_.setRotation(mid_rot);
829 midcoords_ = midcoords_;
834 ROS_ERROR(
"[Footcoords::computeMidCoords] transform error: %s", e.what());
839 ROS_ERROR(
"[Footcoords::computeMidCoords] transform error: %s", e.what());
844 ROS_ERROR(
"[Footcoords::computeMidCoords] transform error: %s", e.what());
848 ROS_ERROR(
"[Footcoords::computeMidCoords] transform error: %s", e.what());
854 bool Footcoords::waitForSensorFrameTransformation(
const ros::Time& lstamp,
856 const std::string& lsensor_frame,
857 const std::string& rsensor_frame)
860 if (!tf_listener_->waitForTransform(
861 lsensor_frame, lfoot_sensor_frame_, lstamp,
ros::Duration(1.0))) {
862 ROS_ERROR(
"[Footcoords::waitForSensorFrameTransformation] failed to lookup transform between %s and %s",
863 lsensor_frame.c_str(),
864 lfoot_sensor_frame_.c_str());
867 if (!tf_listener_->waitForTransform(
868 rsensor_frame, rfoot_sensor_frame_, rstamp,
ros::Duration(1.0))) {
869 ROS_ERROR(
"[Footcoords::waitForSensorFrameTransformation] failed to lookup transform between %s and %s",
870 rsensor_frame.c_str(),
871 rfoot_sensor_frame_.c_str());
877 bool Footcoords::waitForEndEffectorTransformation(
const ros::Time& stamp)
880 if (!tf_listener_->waitForTransform(
881 root_frame_id_, lfoot_frame_id_, stamp,
ros::Duration(1.0))) {
882 ROS_ERROR(
"[Footcoords::waitForEndEffectorTrasnformation] failed to lookup transform between %s and %s",
883 root_frame_id_.c_str(),
884 lfoot_frame_id_.c_str());
888 else if (!tf_listener_->waitForTransform(
889 root_frame_id_, rfoot_frame_id_, stamp,
ros::Duration(1.0))) {
890 ROS_ERROR(
"[Footcoords::waitForEndEffectorTrasnformation]failed to lookup transform between %s and %s",
891 root_frame_id_.c_str(),
892 rfoot_frame_id_.c_str());
896 else if (!tf_listener_->waitForTransform(
897 lfoot_frame_id_, rfoot_frame_id_, stamp,
ros::Duration(1.0))) {
898 ROS_ERROR(
"[Footcoords::waitForEndEffectorTrasnformation]failed to lookup transform between %s and %s",
899 lfoot_frame_id_.c_str(),
900 rfoot_frame_id_.c_str());
906 bool Footcoords::updateGroundTF()
913 if (
false && support_status_ == BOTH_GROUND) {
915 ground_transform_ = midcoords_ * locked_midcoords_to_odom_on_ground_;
918 Eigen::Affine3d odom_to_midcoords;
920 Eigen::Affine3d midcoords_to_odom = odom_to_midcoords.inverse();
921 Eigen::Affine3d midcoords_to_odom_on_ground = midcoords_to_odom;
922 midcoords_to_odom_on_ground.translation().z() = 0.0;
923 Eigen::Vector3d zaxis;
924 zaxis[0] = midcoords_to_odom_on_ground(0, 2);
925 zaxis[1] = midcoords_to_odom_on_ground(1, 2);
926 zaxis[2] = midcoords_to_odom_on_ground(2, 2);
927 Eigen::Quaterniond
rot;
928 rot.setFromTwoVectors(zaxis, Eigen::Vector3d(0, 0, 1));
929 midcoords_to_odom_on_ground.rotate(rot);
930 Eigen::Affine3d odom_to_odom_on_ground
931 = odom_to_midcoords * midcoords_to_odom_on_ground;
937 void Footcoords::getRollPitch(
const Eigen::Affine3d& pose,
float& roll,
float& pitch)
939 Eigen::Affine3f posef;
940 jsk_pcl_ros::convertEigenAffine3(
pose, posef);
942 pcl::getEulerAngles(posef, roll, pitch, yaw);
945 float Footcoords::getYaw(
const Eigen::Affine3d& pose)
947 Eigen::Affine3f posef;
948 jsk_pcl_ros::convertEigenAffine3(pose, posef);
949 float roll, pitch, yaw;
950 pcl::getEulerAngles(posef, roll, pitch, yaw);
954 void Footcoords::publishTF(
const ros::Time& stamp)
957 geometry_msgs::TransformStamped ros_midcoords,
958 ros_ground_coords, ros_odom_to_body_coords,
959 ros_body_on_odom_coords, ros_odom_init_coords;
966 header.frame_id = parent_frame_id_;
967 ros_midcoords.header.stamp =
stamp;
968 ros_midcoords.header.frame_id = root_frame_id_;
969 ros_midcoords.child_frame_id = midcoords_frame_id_;
970 ros_ground_coords.header.stamp =
stamp;
971 ros_ground_coords.header.frame_id = parent_frame_id_;
972 ros_ground_coords.child_frame_id = output_frame_id_;
973 ros_odom_to_body_coords.header.stamp =
stamp;
974 ros_odom_to_body_coords.header.frame_id = parent_frame_id_;
975 ros_odom_to_body_coords.child_frame_id = root_frame_id_;
976 ros_body_on_odom_coords.header.stamp =
stamp;
977 ros_body_on_odom_coords.header.frame_id = root_frame_id_;
978 ros_body_on_odom_coords.child_frame_id = body_on_odom_frame_;
979 ros_odom_init_coords.header.stamp =
stamp;
980 if (invert_odom_init_) {
981 ros_odom_init_coords.header.frame_id = odom_init_frame_id_;
982 ros_odom_init_coords.child_frame_id = parent_frame_id_;
984 ros_odom_init_coords.header.frame_id = parent_frame_id_;
985 ros_odom_init_coords.child_frame_id = odom_init_frame_id_;
987 Eigen::Affine3d identity = Eigen::Affine3d::Identity();
989 getRollPitch(odom_pose_, roll, pitch);
990 Eigen::Affine3d body_on_odom_pose = (Eigen::Translation3d(0,
992 odom_pose_.translation()[2]) *
993 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX()) *
994 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()));
995 midcoords_.getRotation().normalize();
996 Eigen::Affine3d odom_init_pose = (Eigen::Translation3d(odom_init_pose_.translation()[0],
997 odom_init_pose_.translation()[1],
998 odom_init_pose_.translation()[2]) *
999 Eigen::AngleAxisd(
getYaw(odom_init_pose_), Eigen::Vector3d::UnitZ()));
1005 if (invert_odom_init_) {
1010 std::vector<geometry_msgs::TransformStamped> tf_transforms;
1011 tf_transforms.push_back(ros_midcoords);
1012 tf_transforms.push_back(ros_ground_coords);
1013 if (publish_odom_tf_) {
1014 tf_transforms.push_back(ros_odom_to_body_coords);
1016 tf_transforms.push_back(ros_body_on_odom_coords);
1017 tf_transforms.push_back(ros_odom_init_coords);
1018 tf_broadcaster_.sendTransform(tf_transforms);
1021 void Footcoords::odomInitTriggerCallback(
const std_msgs::Empty& trigger)
1023 boost::mutex::scoped_lock
lock(mutex_);
1026 floor_plane.project(odom_pose_, odom_init_pose_);
1027 odom_init_pose_ = (Eigen::Translation3d(odom_init_pose_.translation()) *
1028 Eigen::AngleAxisd(
getYaw(odom_pose_), Eigen::Vector3d::UnitZ()));
1032 geometry_msgs::TransformStamped ros_odom_init_coords;
1033 geometry_msgs::PoseStamped ros_odom_init_pose_stamped;
1034 Eigen::Affine3d odom_init_pose = (Eigen::Translation3d(odom_init_pose_.translation()[0],
1035 odom_init_pose_.translation()[1],
1036 odom_init_pose_.translation()[2]) *
1037 Eigen::AngleAxisd(
getYaw(odom_init_pose_), Eigen::Vector3d::UnitZ()));
1039 ros_odom_init_coords.header.frame_id = parent_frame_id_;
1040 ros_odom_init_coords.child_frame_id = odom_init_frame_id_;
1042 pub_odom_init_transform_.publish(ros_odom_init_coords);
1043 ros_odom_init_pose_stamped.header = ros_odom_init_coords.header;
1044 ros_odom_init_pose_stamped.pose.position.x = ros_odom_init_coords.transform.translation.x;
1045 ros_odom_init_pose_stamped.pose.position.y = ros_odom_init_coords.transform.translation.y;
1046 ros_odom_init_pose_stamped.pose.position.z = ros_odom_init_coords.transform.translation.z;
1047 ros_odom_init_pose_stamped.pose.orientation = ros_odom_init_coords.transform.rotation;
1048 pub_odom_init_pose_stamped_.publish(ros_odom_init_pose_stamped);
1051 void Footcoords::floorCoeffsCallback(
const pcl_msgs::ModelCoefficients& coeffs)
1053 boost::mutex::scoped_lock
lock(mutex_);
1057 if (coeffs.header.frame_id != parent_frame_id_) {
1059 tf_listener_->lookupTransform(odom_init_frame_id_, coeffs.header.frame_id, coeffs.header.stamp, floor_transform);
1061 ROS_ERROR(
"[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1064 ROS_ERROR(
"[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1067 ROS_ERROR(
"[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1070 ROS_ERROR(
"[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1073 Eigen::Affine3d floor_transform_eigen;
1076 tmp_plane.transform(floor_transform_eigen);
1077 floor_coeffs_ = tmp_plane.toCoefficients();
1079 floor_coeffs_ = coeffs.values;
1083 void Footcoords::odomImuCallback(
const nav_msgs::Odometry::ConstPtr& odom_msg,
1084 const sensor_msgs::Imu::ConstPtr& imu_msg)
1088 Eigen::Affine3d odom_pose;
1090 Eigen::Quaterniond imu_orientation;
1093 odom_pose_ = Eigen::Translation3d(odom_pose.translation()) * imu_orientation;
1097 getRollPitch(Eigen::Affine3d::Identity() * imu_orientation, roll, pitch);
1098 odom_pose_ = (Eigen::Translation3d(odom_pose.translation()) *
1099 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX()) *
1100 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()));