footcoords.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
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>
43 #include <tf_conversions/tf_kdl.h>
44 #include <geometry_msgs/TwistStamped.h>
46 #include <boost/assign/list_of.hpp>
47 
49 {
50 
52  diagnostic_updater_(new diagnostic_updater::Updater)
53  {
54  ros::NodeHandle nh, pnh("~");
55  tf_listener_.reset(new tf::TransformListener());
56  odom_status_ = UNINITIALIZED;
57  odom_pose_ = Eigen::Affine3d::Identity();
58  ground_transform_.setRotation(tf::Quaternion(0, 0, 0, 1));
59  root_link_pose_.setIdentity();
60  midcoords_.setRotation(tf::Quaternion(0, 0, 0, 1));
61  estimated_odom_pose_.setRotation(tf::Quaternion(0, 0, 0, 1));
62  diagnostic_updater_->setHardwareID("none");
63  diagnostic_updater_->add("Support Leg Status", this,
64  &Footcoords::updateLegDiagnostics);
65 
66  // read parameter
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_,
72  std::string("zmp"));
73 
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);
86  KDL::Tree tree;
87  robot_model.initParam("robot_description");
88  if (!kdl_parser::treeFromUrdfModel(robot_model, tree)) {
89  ROS_FATAL("Failed to load robot_description");
90  return;
91  }
92 
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++){
96  ROS_INFO_STREAM("kdl_chain(" << i << ") "
97  << lfoot_chain_.getSegment(i).getJoint().getName().c_str());
98  }
99  for (size_t i=0; i < rfoot_chain_.getNrOfSegments(); i++){
100  ROS_INFO_STREAM("kdl_chain(" << i << ") "
101  << rfoot_chain_.getSegment(i).getJoint().getName().c_str());
102  }
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"));
105  // pnh.param("lfoot_sensor_frame", lfoot_sensor_frame_, std::string("lfsensor"));
106  // pnh.param("rfoot_sensor_frame", rfoot_sensor_frame_, std::string("rfsensor"));
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));
128  }
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);
140  // redundant code due to a bug in boost::assign:list_of
141  // see https://svn.boost.org/trac10/ticket/7364 for more details
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);
149  }
150 
151  Footcoords::~Footcoords()
152  {
153 
154  }
155 
156  void Footcoords::updateLegDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
157  {
158  // air -> warn
159  // single leg, dual leg -> ok
160  if (support_status_ == AIR) {
161  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "On Air");
162  }
163  else {
164  if (support_status_ == LLEG_GROUND) {
165  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Left leg on the ground");
166  }
167  else if (support_status_ == RLEG_GROUND) {
168  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Right leg on the ground");
169  }
170  else if (support_status_ == BOTH_GROUND) {
171  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Both legs on the ground");
172  }
173  }
174  }
175 
176  double Footcoords::applyLowPassFilter(double current_val, double prev_val) const
177  {
178  return prev_val + alpha_ * (current_val - prev_val);
179  }
180 
181  bool Footcoords::allValueLargerThan(TimeStampedVector<ValueStamped::Ptr>& values,
182  double threshold)
183  {
184  for (size_t i = 0; i < values.size(); i++) {
185  if (values[i]->value < threshold) {
186  return false;
187  }
188  }
189  return true;
190  }
191 
192  bool Footcoords::allValueSmallerThan(TimeStampedVector<ValueStamped::Ptr>& values,
193  double threshold)
194  {
195  for (size_t i = 0; i < values.size(); i++) {
196  if (values[i]->value > threshold) {
197  return false;
198  }
199  }
200  return true;
201  }
202 
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)
207  {
208  try {
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");
211  return false;
212  }
213  tf::StampedTransform lfoot_transform, rfoot_transform;
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);
218  // cancel translation
219  lfoot_transform.setOrigin(tf::Vector3(0, 0, 0));
220  rfoot_transform.setOrigin(tf::Vector3(0, 0, 0));
221 
222  tf::Vector3 lfoot_local, rfoot_local;
223  tf::vector3MsgToTF(lfoot.wrench.force, lfoot_local);
224  tf::vector3MsgToTF(rfoot.wrench.force, rfoot_local);
225  lfoot_force = lfoot_transform * lfoot_local;
226  rfoot_force = rfoot_transform * rfoot_local;
227  // lfoot_force = lfoot_rotation * lfoot_local;
228  // rfoot_force = rfoot_rotation * rfoot_local;
229  return true;
230  }
231  catch (tf2::ConnectivityException &e) {
232  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
233  return false;
234  }
236  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
237  return false;
238  }
239  catch (tf2::ExtrapolationException &e) {
240  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
241  return false;
242  }
243  catch (tf2::LookupException &e) {
244  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
245  return false;
246  }
247  }
248 
249  void Footcoords::periodicTimerCallback(const ros::TimerEvent& event)
250  {
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");
255  }
256  else {
257  if (support_status_ == LLEG_GROUND) {
258  publishState("lfoot");
259  }
260  else if (support_status_ == RLEG_GROUND) {
261  publishState("rfoot");
262  }
263  }
264  //if (success_to_update) {
265  tf::StampedTransform root_transform;
266  try {
267  // tf_listener_->lookupTransform(parent_frame_id_, root_frame_id_, event.current_real, root_transform);
268  // root_link_pose_.setOrigin(root_transform.getOrigin());
269  // root_link_pose_.setRotation(root_transform.getRotation());
270  }
271  catch (tf2::ConnectivityException &e) {
272  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
273  }
274  catch (tf2::InvalidArgumentException &e) {
275  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
276  }
277  catch (tf2::ExtrapolationException &e) {
278  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
279  }
280  catch (tf2::LookupException &e) {
281  ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
282  }
283  //}
284 
285  // midcoords is a center coordinates of two feet
286  // compute root_link -> midcoords
287  // root_link_pose_ := odom -> root_link
288  // midcoords_ := odom -> midcoords
289  // root_link_pose_ * T = midcoords_
290  // T = root_link_pose_^-1 * midcoords_
291  //ground_transform_ = root_link_pose_.inverse() * midcoords_;
292  ground_transform_ = midcoords_;
293  publishTF(event.current_real);
294  diagnostic_updater_->update();
295  publishContactState(event.current_real);
296  }
297 
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)
302  {
303  jsk_footstep_controller::SynchronizedForces forces;
304  forces.header = lfoot->header;
305  forces.lleg_force = *lfoot;
306  forces.rleg_force = *rfoot;
307  forces.joint_angles = *joint_states;
308  forces.zmp = *zmp;
309  pub_synchronized_forces_.publish(forces);
310  Eigen::Vector3d zmp_point;
311  tf::pointMsgToEigen(zmp->point, zmp_point);
312  // Just for visualization
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);
318  tf::transformEigenToMsg(zmp_pose, ros_zmp_coords.transform);
319  std::vector<geometry_msgs::TransformStamped> tf_transforms;
320  tf_transforms.push_back(ros_zmp_coords);
321  {
322  boost::mutex::scoped_lock lock(mutex_);
323  tf_broadcaster_.sendTransform(tf_transforms);
324  }
325  }
326  }
327 
328  void Footcoords::updateChain(std::map<std::string, double>& joint_angles,
329  KDL::Chain& chain,
330  tf::Pose& output_pose)
331  {
332  KDL::JntArray jnt_pos(chain.getNrOfJoints());
333  for (int i = 0, j = 0; i < chain.getNrOfSegments(); i++) {
334  /*
335  * if (chain.getSegment(i).getJoint().getType() == KDL::Joint::None)
336  * continue;
337  */
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];
341  }
342  }
343  KDL::ChainFkSolverPos_recursive fk_solver(chain);
344  KDL::Frame pose;
345  if (fk_solver.JntToCart(jnt_pos, pose) < 0) {
346  ROS_FATAL("Failed to compute FK");
347  }
348  tf::poseKDLToTF(pose, output_pose);
349  }
350 
351  void Footcoords::updateRobotModel(std::map<std::string, double>& joint_angles)
352  {
353 
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;
357  tf::poseTFToMsg(lfoot_pose_, ros_lfoot_pose);
358  tf::poseTFToMsg(rfoot_pose_, ros_rfoot_pose);
359  pub_debug_lfoot_pos_.publish(ros_lfoot_pose);
360  pub_debug_rfoot_pos_.publish(ros_rfoot_pose);
361  }
362 
363  void Footcoords::computeVelicity(double dt,
364  std::map<std::string, double>& joint_angles,
365  KDL::Chain& chain,
366  geometry_msgs::Twist& output)
367  {
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];
376  }
377  }
378  jnt_pos.q = q;
379  jnt_pos.qdot = qdot;
380  KDL::FrameVel vel;
381  if (fk_solver.JntToCart(jnt_pos, vel) < 0) {
382  ROS_FATAL("Failed to compute velocity");
383  }
384  KDL::Twist twist = vel.GetTwist();
385  tf::twistKDLToMsg(twist, output);
386  }
387 
388  void Footcoords::estimateVelocity(const ros::Time& stamp, std::map<std::string, double>& joint_angles)
389  {
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);
395  }
396  else if (odom_status_ == RLEG_SUPPORT) {
397  computeVelicity(dt, joint_angles, rfoot_chain_, twist_stamped.twist);
398  }
399  twist_stamped.header.stamp = stamp;
400  twist_stamped.header.frame_id = root_frame_id_;
401  pub_twist_.publish(twist_stamped);
402  }
403  }
404 
405  void Footcoords::filter(const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg)
406  {
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];
415  }
416 
417  updateRobotModel(angles);
418 
419  // lowpass filter
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");
423  return;
424  }
425  // resolve tf
426  double lfoot_force = applyLowPassFilter(lfoot_force_vector[2], prev_lforce_);
427  double rfoot_force = applyLowPassFilter(rfoot_force_vector[2], prev_rforce_);
428 
429  // publish lowlevel info
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;
440 
441  if (lfoot_force >= force_thr_ && rfoot_force >= force_thr_) {
442  support_status_ = BOTH_GROUND;
443  }
444  else if (lfoot_force < force_thr_ && rfoot_force < force_thr_) {
445  support_status_ = AIR;
446  }
447  else if (lfoot_force >= force_thr_) {
448  // only left
449  support_status_ = LLEG_GROUND;
450  }
451  else if (rfoot_force >= force_thr_) {
452  // only right
453  support_status_ = RLEG_GROUND;
454  }
455  estimateOdometry();
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_;
460  tf::poseTFToMsg(estimated_odom_pose_, leg_odometory.pose);
461  pub_leg_odometory_.publish(leg_odometory);
462  /* tf for debug*/
463  std::vector<geometry_msgs::TransformStamped> tf_transforms;
464  geometry_msgs::TransformStamped odom_transform;
465  tf::transformTFToMsg(estimated_odom_pose_, odom_transform.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);
470  prev_joints_ = angles;
471  last_time_ = msg->header.stamp;
472  }
473 
474  void Footcoords::estimateOdometry()
475  {
476  //estimateOdometryMainSupportLeg();
477  estimateOdometryZMPSupportLeg();
478  }
479 
480  void Footcoords::estimateOdometryNaive()
481  {
482  if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
483  ROS_INFO("changed to INITIALIZING");
484  odom_status_ = INITIALIZING;
485  }
486  if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
487  ROS_INFO_THROTTLE(1.0, "INITIALIZING");
488  /* Update odom origin */
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);
491  tf::Pose midcoords;
492  midcoords.setOrigin(midcoords_pos);
493  midcoords.setRotation(midcoords_rot);
494  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
495  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
496  estimated_odom_pose_ = midcoords;
497  }
498  if (odom_status_ == INITIALIZING && support_status_ ==RLEG_GROUND) {
499  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
500  odom_status_ = RLEG_SUPPORT;
501  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
502  }
503  else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
504  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
505  odom_status_ = LLEG_SUPPORT;
506  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
507  }
508  else if (odom_status_ == RLEG_SUPPORT && support_status_ == RLEG_GROUND) {
509  ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
510  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
511  }
512  else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
513  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
514  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
515  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
516  }
517  else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
518  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
519  odom_status_ = LLEG_SUPPORT;
520  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
521  }
522  else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
523  ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
524  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
525  }
526  else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
527  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
528  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
529  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
530  }
531  else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
532  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
533  odom_status_ = RLEG_SUPPORT;
534  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
535  }
536  if (support_status_ == AIR) {
537  ROS_INFO_THROTTLE(1.0, "resetting");
538  odom_status_ = UNINITIALIZED;
539  }
540  }
541 
542  void Footcoords::estimateOdometryMainSupportLeg()
543  {
544  if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
545  ROS_INFO("changed to INITIALIZING");
546  odom_status_ = INITIALIZING;
547  }
548  if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
549  ROS_INFO_THROTTLE(1.0, "INITIALIZING");
550  /* Update odom origin */
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);
553  tf::Pose midcoords;
554  midcoords.setOrigin(midcoords_pos);
555  midcoords.setRotation(midcoords_rot);
556  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
557  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
558  estimated_odom_pose_ = midcoords;
559  }
560  if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
561  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
562  odom_status_ = RLEG_SUPPORT;
563  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
564  }
565  else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
566  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
567  odom_status_ = LLEG_SUPPORT;
568  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
569  }
570  else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
571  ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
572  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
573  }
574  else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
575  if (prev_lforce_ > prev_rforce_) {
576  /* switch to lleg */
577  odom_status_ = LLEG_SUPPORT;
578  ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to lleg");
579  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
580  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
581  }
582  else {
583  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
584  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
585  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
586  }
587  }
588  else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
589  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
590  odom_status_ = LLEG_SUPPORT;
591  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
592  }
593  else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
594  ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
595  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
596  }
597  else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
598  if (prev_rforce_ > prev_lforce_) {
599  odom_status_ = RLEG_SUPPORT;
600  ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to rleg");
601  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
602  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
603  }
604  else {
605  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
606  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
607  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
608  }
609  }
610  else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
611  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
612  odom_status_ = RLEG_SUPPORT;
613  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
614  }
615  if (support_status_ == AIR) {
616  ROS_INFO_THROTTLE(1.0, "resetting");
617  odom_status_ = UNINITIALIZED;
618  }
619  }
620 
621  void Footcoords::estimateOdometryZMPSupportLeg()
622  {
623  if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
624  ROS_INFO("changed to INITIALIZING");
625  odom_status_ = INITIALIZING;
626  }
627  if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
628  ROS_INFO_THROTTLE(1.0, "INITIALIZING");
629  /* Update odom origin */
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);
632  tf::Pose midcoords;
633  midcoords.setOrigin(midcoords_pos);
634  midcoords.setRotation(midcoords_rot);
635  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
636  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
637  estimated_odom_pose_ = midcoords;
638  }
639  if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
640  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
641  odom_status_ = RLEG_SUPPORT;
642  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
643  }
644  else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
645  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
646  odom_status_ = LLEG_SUPPORT;
647  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
648  }
649  else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
650  ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
651  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
652  }
653  else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
654  if (zmp_[1] > 0) {
655  /* switch to lleg */
656  odom_status_ = LLEG_SUPPORT;
657  ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to lleg");
658  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
659  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
660  }
661  else {
662  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
663  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
664  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
665  }
666  }
667  else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
668  ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
669  odom_status_ = LLEG_SUPPORT;
670  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
671  }
672  else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
673  ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
674  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
675  }
676  else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
677  if (zmp_[1] < 0) {
678  odom_status_ = RLEG_SUPPORT;
679  ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to rleg");
680  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
681  lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
682  }
683  else {
684  ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
685  estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
686  rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
687  }
688  }
689  else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
690  ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
691  odom_status_ = RLEG_SUPPORT;
692  estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
693  }
694  if (support_status_ == AIR) {
695  ROS_INFO_THROTTLE(1.0, "resetting");
696  odom_status_ = UNINITIALIZED;
697  }
698  }
699 
700 
701 
702  void Footcoords::publishState(const std::string& state)
703  {
704  std_msgs::String state_msg;
705  state_msg.data = state;
706  pub_state_.publish(state_msg);
707  }
708 
709  void Footcoords::publishContactState(const ros::Time& stamp)
710  {
711  GroundContactState contact_state;
712  contact_state.header.stamp = stamp;
713  if (support_status_ == AIR) {
714  contact_state.contact_state
715  = GroundContactState::CONTACT_AIR;
716  }
717  else if (support_status_ == LLEG_GROUND) {
718  contact_state.contact_state
719  = GroundContactState::CONTACT_LLEG_GROUND;
720  }
721  else if (support_status_ == RLEG_GROUND) {
722  contact_state.contact_state
723  = GroundContactState::CONTACT_RLEG_GROUND;
724  }
725  else if (support_status_ == BOTH_GROUND) {
726  contact_state.contact_state
727  = GroundContactState::CONTACT_BOTH_GROUND;
728  }
729  try
730  {
731  tf::StampedTransform foot_transform;
732  tf_listener_->lookupTransform(
733  lfoot_frame_id_, rfoot_frame_id_, stamp, foot_transform);
734  double roll, pitch, yaw;
735  foot_transform.getBasis().getRPY(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);
741  }
742  catch (tf2::ConnectivityException &e)
743  {
744  ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
745  }
747  {
748  ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
749  }
750  catch (tf2::ExtrapolationException &e)
751  {
752  ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
753  }
754  catch (tf2::LookupException &e)
755  {
756  ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
757  }
758 
759  }
760 
761  bool Footcoords::computeMidCoordsFromSingleLeg(const ros::Time& stamp,
762  bool use_left_leg)
763  {
764  if (!waitForEndEffectorTransformation(stamp)) {
765  ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] Failed to lookup endeffector transformation");
766  return false;
767  }
768  else {
769  try
770  {
771  tf::StampedTransform foot_transform; // parent -> foot
772  if (use_left_leg) { // left on the ground
773  tf_listener_->lookupTransform(
774  root_frame_id_, lfoot_frame_id_, stamp, foot_transform);
775  }
776  else { // right on the ground
777  tf_listener_->lookupTransform(
778  root_frame_id_, rfoot_frame_id_, stamp, foot_transform);
779  }
780  midcoords_ = foot_transform.inverse();
781  return true;
782  }
783  catch (tf2::ConnectivityException &e)
784  {
785  ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
786  return false;
787  }
789  {
790  ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
791  return false;
792  }
794  {
795  ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
796  }
797  catch (tf2::LookupException &e)
798  {
799  ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
800  }
801 
802 
803  }
804  }
805 
806  bool Footcoords::computeMidCoords(const ros::Time& stamp)
807  {
808  if (!waitForEndEffectorTransformation(stamp)) {
809  ROS_ERROR("[Footcoords::computeMidCoords] Failed to lookup endeffector transformation");
810  return false;
811  }
812  else {
813  try
814  {
815  tf::StampedTransform lfoot_transform;
816  tf_listener_->lookupTransform(
817  root_frame_id_, lfoot_frame_id_, stamp, lfoot_transform);
818  tf::StampedTransform rfoot_transform;
819  tf_listener_->lookupTransform(
820  root_frame_id_, rfoot_frame_id_, stamp, rfoot_transform);
821  tf::Quaternion lfoot_rot = lfoot_transform.getRotation();
822  tf::Quaternion rfoot_rot = rfoot_transform.getRotation();
823  tf::Quaternion mid_rot = lfoot_rot.slerp(rfoot_rot, 0.5);
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_;
830  return true;
831  }
832  catch (tf2::ConnectivityException &e)
833  {
834  ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
835  return false;
836  }
838  {
839  ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
840  return false;
841  }
842  catch (tf2::ExtrapolationException &e)
843  {
844  ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
845  }
846  catch (tf2::LookupException &e)
847  {
848  ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
849  }
850 
851  }
852  }
853 
854  bool Footcoords::waitForSensorFrameTransformation(const ros::Time& lstamp,
855  const ros::Time& rstamp,
856  const std::string& lsensor_frame,
857  const std::string& rsensor_frame)
858  {
859  // lfsensor -> lleg_end_coords
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());
865  return false;
866  }
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());
872  return false;
873  }
874  return true;
875  }
876 
877  bool Footcoords::waitForEndEffectorTransformation(const ros::Time& stamp)
878  {
879  // odom -> lfoot
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());
885  return false;
886  }
887  // odom -> rfoot
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());
893  return false;
894  }
895  // lfoot -> rfoot
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());
901  return false;
902  }
903  return true;
904  }
905 
906  bool Footcoords::updateGroundTF()
907  {
908  // project `/odom` on the plane of midcoords_
909  // odom -> midcoords is available as `midcoords_`
910  // we need odom -> odom_on_ground
911  // 1. in order to get translation,
912  // project odom point to
913  if (false && support_status_ == BOTH_GROUND) {
914  // use locked_midcoords_to_odom_on_ground_ during dual stance phase
915  ground_transform_ = midcoords_ * locked_midcoords_to_odom_on_ground_;
916  }
917  else {
918  Eigen::Affine3d odom_to_midcoords;
919  tf::transformTFToEigen(midcoords_, 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;
932  tf::transformEigenToTF(odom_to_odom_on_ground,
933  ground_transform_);
934  }
935  }
936 
937  void Footcoords::getRollPitch(const Eigen::Affine3d& pose, float& roll, float& pitch)
938  {
939  Eigen::Affine3f posef;
940  jsk_pcl_ros::convertEigenAffine3(pose, posef);
941  float yaw;
942  pcl::getEulerAngles(posef, roll, pitch, yaw);
943  }
944 
945  float Footcoords::getYaw(const Eigen::Affine3d& pose)
946  {
947  Eigen::Affine3f posef;
948  jsk_pcl_ros::convertEigenAffine3(pose, posef);
949  float roll, pitch, yaw;
950  pcl::getEulerAngles(posef, roll, pitch, yaw);
951  return yaw;
952  }
953 
954  void Footcoords::publishTF(const ros::Time& stamp)
955  {
956  // publish midcoords_ and ground_cooords_
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;
960  // ros_midcoords: ROOT -> ground
961  // ros_ground_coords: odom -> odom_on_ground = identity
962  // ros_odom_root_coords: odom -> odom_root = identity
963  // ros_ground_coords: odom_root -> odom_on_ground = identity
964  std_msgs::Header header;
965  header.stamp = stamp;
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_;
983  } else {
984  ros_odom_init_coords.header.frame_id = parent_frame_id_;
985  ros_odom_init_coords.child_frame_id = odom_init_frame_id_;
986  }
987  Eigen::Affine3d identity = Eigen::Affine3d::Identity();
988  float roll, pitch;
989  getRollPitch(odom_pose_, roll, pitch);
990  Eigen::Affine3d body_on_odom_pose = (Eigen::Translation3d(0,
991  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()));
1000 
1001  tf::transformTFToMsg(midcoords_, ros_midcoords.transform);
1002  tf::transformEigenToMsg(identity, ros_ground_coords.transform);
1003  tf::transformEigenToMsg(body_on_odom_pose.inverse(), ros_body_on_odom_coords.transform);
1004  tf::transformEigenToMsg(odom_pose_, ros_odom_to_body_coords.transform);
1005  if (invert_odom_init_) {
1006  tf::transformEigenToMsg(odom_init_pose.inverse(), ros_odom_init_coords.transform);
1007  } else {
1008  tf::transformEigenToMsg(odom_init_pose, ros_odom_init_coords.transform);
1009  }
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);
1015  }
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);
1019  }
1020 
1021  void Footcoords::odomInitTriggerCallback(const std_msgs::Empty& trigger)
1022  {
1023  boost::mutex::scoped_lock lock(mutex_);
1024  // Update odom_init_pose
1025  jsk_recognition_utils::Plane floor_plane(floor_coeffs_);
1026  floor_plane.project(odom_pose_, odom_init_pose_); // this projection do not consider yaw orientations
1027  odom_init_pose_ = (Eigen::Translation3d(odom_init_pose_.translation()) *
1028  Eigen::AngleAxisd(getYaw(odom_pose_), Eigen::Vector3d::UnitZ())); // assuming that projected plane is horizontal
1029 
1030  // publish odom_init topics
1031  // whether invert_odom_init is true or not odom_init_pose_stamped and odom_init_transform is described in odom coordinates.
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()));
1038  ros_odom_init_coords.header.stamp = ros::Time::now();
1039  ros_odom_init_coords.header.frame_id = parent_frame_id_;
1040  ros_odom_init_coords.child_frame_id = odom_init_frame_id_;
1041  tf::transformEigenToMsg(odom_init_pose, ros_odom_init_coords.transform);
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);
1049  }
1050 
1051  void Footcoords::floorCoeffsCallback(const pcl_msgs::ModelCoefficients& coeffs)
1052  {
1053  boost::mutex::scoped_lock lock(mutex_);
1054  tf::StampedTransform floor_transform;
1055 
1056  // floor_coords is expected to be described in parent_frame_id_ relative coordinate
1057  if (coeffs.header.frame_id != parent_frame_id_) {
1058  try {
1059  tf_listener_->lookupTransform(odom_init_frame_id_, coeffs.header.frame_id, coeffs.header.stamp, floor_transform);
1060  } catch (tf2::ConnectivityException &e) {
1061  ROS_ERROR("[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1062  return;
1063  } catch (tf2::InvalidArgumentException &e) {
1064  ROS_ERROR("[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1065  return;
1066  } catch (tf2::ExtrapolationException &e) {
1067  ROS_ERROR("[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1068  return;
1069  } catch (tf2::LookupException &e) {
1070  ROS_ERROR("[Footcoords::floorCoeffsCallback] transform error: %s", e.what());
1071  return;
1072  }
1073  Eigen::Affine3d floor_transform_eigen;
1074  jsk_recognition_utils::Plane tmp_plane(coeffs.values);
1075  tf::transformTFToEigen(floor_transform, floor_transform_eigen);
1076  tmp_plane.transform(floor_transform_eigen);
1077  floor_coeffs_ = tmp_plane.toCoefficients();
1078  } else {
1079  floor_coeffs_ = coeffs.values;
1080  }
1081  }
1082 
1083  void Footcoords::odomImuCallback(const nav_msgs::Odometry::ConstPtr& odom_msg,
1084  const sensor_msgs::Imu::ConstPtr& imu_msg)
1085  {
1086  boost::mutex::scoped_lock lock(mutex_);
1087  if (use_imu_) {
1088  Eigen::Affine3d odom_pose;
1089  tf::poseMsgToEigen(odom_msg->pose.pose, odom_pose);
1090  Eigen::Quaterniond imu_orientation;
1091  tf::quaternionMsgToEigen(imu_msg->orientation, imu_orientation);
1092  if (use_imu_yaw_) {
1093  odom_pose_ = Eigen::Translation3d(odom_pose.translation()) * imu_orientation;
1094  }
1095  else {
1096  float roll, pitch;
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()));
1101  }
1102  }
1103  else {
1104  tf::poseMsgToEigen(odom_msg->pose.pose, odom_pose_);
1105  }
1106  }
1107 }
1108 
1109 int main(int argc, char** argv)
1110 {
1111  ros::init(argc, argv, "footcoords");
1113  ros::spin();
1114 }
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
tf::Transform::getRotation
Quaternion getRotation() const
rot
rot
tf::transformTFToMsg
static void transformTFToMsg(const Transform &bt, geometry_msgs::Transform &msg)
msg
msg
angles
tf::transformEigenToTF
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
i
int i
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
header
header
value
value
tf::Matrix3x3::getRPY
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
tf::twistKDLToMsg
void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m)
tf::quaternionMsgToEigen
void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
tf::pointMsgToEigen
void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
tf::vector3MsgToTF
static void vector3MsgToTF(const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
tf::poseTFToMsg
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
urdf::Model
c
c
tf::Transform::getBasis
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
tf::StampedTransform
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
main
int main(int argc, char **argv)
Definition: footcoords.cpp:1109
mutex_
boost::mutex mutex_
pose
pose
tf::Quaternion::slerp
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
tf_eigen.h
tf::Transform::inverse
Transform inverse() const
tf::Transform::setRotation
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
diagnostic_updater
q
q
tf2::ExtrapolationException
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
tf::poseKDLToTF
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
jsk_footstep_controller
Definition: footcoords.h:61
argv
ROS_INFO ROS_ERROR int pointer * argv
ROS_ERROR
#define ROS_ERROR(...)
kdl_msg.h
stamp
stamp
lock
mutex_t * lock
tf2::LookupException
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
tf::Transform
info
info
joint_states
joint_states
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
ros::TimerEvent::current_real
Time current_real
robot_model
robot_model
pcl_conversion_util.h
tf2::ConnectivityException
ROS_FATAL
#define ROS_FATAL(...)
state
state
jsk_footstep_controller::Footcoords
Definition: footcoords.h:129
tree
pcl::KdTreeFLANN< pcl::PointNormal > tree
getYaw
double getYaw(const tf2::Quaternion &q)
ros::Time
values
long long values[]
tf_kdl.h
tf::TransformListener
diagnostic_updater::DiagnosticStatusWrapper
jsk_recognition_utils::Plane
jsk_footstep_controller::Footcoords::Footcoords
Footcoords()
Definition: footcoords.cpp:83
ros::spin
ROSCPP_DECL void spin()
footcoords.h
tf::transformEigenToMsg
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
tf2::InvalidArgumentException
ROS_INFO
#define ROS_INFO(...)
ros::Duration
tf::Quaternion
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
ros::NodeHandle
ros::Time::now
static Time now()
ROS_INFO_THROTTLE
#define ROS_INFO_THROTTLE(period,...)


jsk_footstep_controller
Author(s):
autogenerated on Mon Dec 9 2024 04:11:17