footcoords.cpp
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include <jsk_topic_tools/rosparam_utils.h>
00037 #include "jsk_footstep_controller/footcoords.h"
00038 #include <std_msgs/String.h>
00039 #include <tf_conversions/tf_eigen.h>
00040 #include <jsk_pcl_ros/pcl_conversion_util.h>
00041 #include <tf_conversions/tf_eigen.h>
00042 #include <jsk_pcl_ros/pcl_conversion_util.h>
00043 #include <kdl/chainfksolverpos_recursive.hpp>
00044 #include <kdl/chainfksolvervel_recursive.hpp>
00045 #include <tf_conversions/tf_kdl.h>
00046 #include <geometry_msgs/TwistStamped.h>
00047 #include <kdl_conversions/kdl_msg.h>
00048 
00049 namespace jsk_footstep_controller
00050 {
00051 
00052   Footcoords::Footcoords():
00053     diagnostic_updater_(new diagnostic_updater::Updater)
00054   {
00055     ros::NodeHandle nh, pnh("~");
00056     tf_listener_.reset(new tf::TransformListener());
00057     odom_status_ = UNINITIALIZED;
00058     odom_pose_ = Eigen::Affine3d::Identity();
00059     ground_transform_.setRotation(tf::Quaternion(0, 0, 0, 1));
00060     root_link_pose_.setIdentity();
00061     midcoords_.setRotation(tf::Quaternion(0, 0, 0, 1));
00062     estimated_odom_pose_.setRotation(tf::Quaternion(0, 0, 0, 1));
00063     diagnostic_updater_->setHardwareID("none");
00064     diagnostic_updater_->add("Support Leg Status", this,
00065                              &Footcoords::updateLegDiagnostics);
00066 
00067     // read parameter
00068     pnh.param("alpha", alpha_, 0.1);
00069     pnh.param("sampling_time_", sampling_time_, 0.2);
00070     pnh.param("output_frame_id", output_frame_id_,
00071               std::string("odom_on_ground"));
00072     pnh.param("zmp_frame_id", zmp_frame_id_,
00073               std::string("zmp"));
00074 
00075     pnh.param("parent_frame_id", parent_frame_id_, std::string("odom"));
00076     pnh.param("midcoords_frame_id", midcoords_frame_id_, std::string("ground"));
00077     pnh.param("root_frame_id", root_frame_id_, std::string("BODY"));
00078     pnh.param("body_on_odom_frame", body_on_odom_frame_, std::string("body_on_odom"));
00079     pnh.param("odom_init_frame_id", odom_init_frame_id_, std::string("odom_init"));
00080     pnh.param("lfoot_frame_id", lfoot_frame_id_,
00081               std::string("lleg_end_coords"));
00082     pnh.param("rfoot_frame_id", rfoot_frame_id_,
00083               std::string("rleg_end_coords"));
00084     pnh.param("publish_odom_tf", publish_odom_tf_, true);
00085     urdf::Model robot_model;
00086     KDL::Tree tree;
00087     robot_model.initParam("robot_description");
00088     if (!kdl_parser::treeFromUrdfModel(robot_model, tree)) {
00089       ROS_FATAL("Failed to load robot_description");
00090       return;
00091     }
00092 
00093     tree.getChain(root_frame_id_, lfoot_frame_id_, lfoot_chain_);
00094     tree.getChain(root_frame_id_, rfoot_frame_id_, rfoot_chain_);
00095     for (size_t i=0; i < lfoot_chain_.getNrOfSegments(); i++){
00096       ROS_INFO_STREAM("kdl_chain(" << i << ") "
00097                       << lfoot_chain_.getSegment(i).getJoint().getName().c_str());
00098     }
00099     for (size_t i=0; i < rfoot_chain_.getNrOfSegments(); i++){
00100       ROS_INFO_STREAM("kdl_chain(" << i << ") "
00101                       << rfoot_chain_.getSegment(i).getJoint().getName().c_str());
00102     }
00103     pnh.param("lfoot_sensor_frame", lfoot_sensor_frame_, std::string("lleg_end_coords"));
00104     pnh.param("rfoot_sensor_frame", rfoot_sensor_frame_, std::string("rleg_end_coords"));
00105     // pnh.param("lfoot_sensor_frame", lfoot_sensor_frame_, std::string("lfsensor"));
00106     // pnh.param("rfoot_sensor_frame", rfoot_sensor_frame_, std::string("rfsensor"));
00107     pnh.param("force_threshold", force_thr_, 200.0);
00108     support_status_ = AIR;
00109     pub_low_level_ = pnh.advertise<jsk_footstep_controller::FootCoordsLowLevelInfo>("low_level_info", 1);
00110     pub_state_ = pnh.advertise<std_msgs::String>("state", 1);
00111     pub_contact_state_ = pnh.advertise<jsk_footstep_controller::GroundContactState>("contact_state", 1);
00112     pub_synchronized_forces_ = pnh.advertise<jsk_footstep_controller::SynchronizedForces>("synchronized_forces", 1);
00113     pub_debug_lfoot_pos_ = pnh.advertise<geometry_msgs::Pose>("debug/lfoot_pose", 1);
00114     pub_debug_rfoot_pos_ = pnh.advertise<geometry_msgs::Pose>("debug/rfoot_pose", 1);
00115     pub_leg_odometory_ = pnh.advertise<geometry_msgs::PoseStamped>("leg_odometry", 1);
00116     pub_twist_ = pnh.advertise<geometry_msgs::TwistStamped>("base_vel", 1);
00117     before_on_the_air_ = true;
00118     pnh.param("use_imu", use_imu_, false);
00119     pnh.param("use_imu_yaw", use_imu_yaw_, true);
00120     if (publish_odom_tf_) {
00121       odom_sub_.subscribe(pnh, "/odom", 50);
00122       imu_sub_.subscribe(pnh, "/imu", 50);
00123       odom_imu_sync_ = boost::make_shared<message_filters::Synchronizer<OdomImuSyncPolicy> >(100);
00124       odom_imu_sync_->connectInput(odom_sub_, imu_sub_);
00125       odom_imu_sync_->registerCallback(boost::bind(&Footcoords::odomImuCallback, this, _1, _2));
00126     }
00127     odom_init_pose_ = Eigen::Affine3d::Identity();
00128     odom_init_trigger_sub_ = pnh.subscribe("/odom_init_trigger", 1,
00129                                            &Footcoords::odomInitTriggerCallback, this);
00130     periodic_update_timer_ = pnh.createTimer(ros::Duration(1.0 / 25),
00131                                              boost::bind(&Footcoords::periodicTimerCallback, this, _1));
00132     sub_lfoot_force_.subscribe(nh, "lfsensor", 50);
00133     sub_rfoot_force_.subscribe(nh, "rfsensor", 50);
00134     sub_joint_states_.subscribe(nh, "joint_states",50);
00135     sub_zmp_.subscribe(nh, "zmp", 50);
00136     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00137     sync_->connectInput(sub_lfoot_force_, sub_rfoot_force_, sub_joint_states_, sub_zmp_);
00138     sync_->registerCallback(boost::bind(&Footcoords::synchronizeForces, this, _1, _2, _3, _4));
00139     synchronized_forces_sub_ = pnh.subscribe("synchronized_forces", 20,
00140                                              &Footcoords::filter, this);
00141   }
00142 
00143   Footcoords::~Footcoords()
00144   {
00145 
00146   }
00147 
00148   void Footcoords::updateLegDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
00149   {
00150     // air -> warn
00151     // single leg, dual leg -> ok
00152     if (support_status_ == AIR) {
00153       stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "On Air");
00154     }
00155     else {
00156       if (support_status_ == LLEG_GROUND) {
00157         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Left leg on the ground");
00158       }
00159       else if (support_status_ == RLEG_GROUND) {
00160         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Right leg on the ground");
00161       }
00162       else if (support_status_ == BOTH_GROUND) {
00163         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Both legs on the ground");
00164       }
00165     }
00166   }
00167 
00168   double Footcoords::applyLowPassFilter(double current_val, double prev_val) const
00169   {
00170     return prev_val + alpha_ * (current_val - prev_val);
00171   }
00172 
00173   bool Footcoords::allValueLargerThan(TimeStampedVector<ValueStamped::Ptr>& values,
00174                                       double threshold)
00175   {
00176     for (size_t i = 0; i < values.size(); i++) {
00177       if (values[i]->value < threshold) {
00178         return false;
00179       }
00180     }
00181     return true;
00182   }
00183 
00184   bool Footcoords::allValueSmallerThan(TimeStampedVector<ValueStamped::Ptr>& values,
00185                                         double threshold)
00186   {
00187     for (size_t i = 0; i < values.size(); i++) {
00188       if (values[i]->value > threshold) {
00189         return false;
00190       }
00191     }
00192     return true;
00193   }
00194 
00195   bool Footcoords::resolveForceTf(const geometry_msgs::WrenchStamped& lfoot,
00196                                   const geometry_msgs::WrenchStamped& rfoot,
00197                                   tf::Vector3& lfoot_force,
00198                                   tf::Vector3& rfoot_force)
00199   {
00200     try {
00201       if (!waitForEndEffectorTrasnformation(lfoot.header.stamp)) {
00202         ROS_ERROR("[Footcoords::resolveForceTf] failed to lookup transformation for sensor value");
00203         return false;
00204       }
00205       tf::StampedTransform lfoot_transform, rfoot_transform;
00206       tf_listener_->lookupTransform(
00207         lfoot.header.frame_id, lfoot_sensor_frame_, lfoot.header.stamp, lfoot_transform);
00208       tf_listener_->lookupTransform(
00209         rfoot.header.frame_id, rfoot_sensor_frame_, rfoot.header.stamp, rfoot_transform);
00210       // cancel translation
00211       lfoot_transform.setOrigin(tf::Vector3(0, 0, 0));
00212       rfoot_transform.setOrigin(tf::Vector3(0, 0, 0));
00213 
00214       tf::Vector3 lfoot_local, rfoot_local;
00215       tf::vector3MsgToTF(lfoot.wrench.force, lfoot_local);
00216       tf::vector3MsgToTF(rfoot.wrench.force, rfoot_local);
00217       lfoot_force = lfoot_transform * lfoot_local;
00218       rfoot_force = rfoot_transform * rfoot_local;
00219       // lfoot_force = lfoot_rotation * lfoot_local;
00220       // rfoot_force = rfoot_rotation * rfoot_local;
00221       return true;
00222     }
00223     catch (tf2::ConnectivityException &e) {
00224       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00225       return false;
00226     }
00227     catch (tf2::InvalidArgumentException &e) {
00228       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00229       return false;
00230     }
00231     catch (tf2::ExtrapolationException &e) {
00232       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00233       return false;
00234     }
00235     catch (tf2::LookupException &e) {
00236       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00237       return false;
00238     }
00239   }
00240 
00241   void Footcoords::periodicTimerCallback(const ros::TimerEvent& event)
00242   {
00243     boost::mutex::scoped_lock lock(mutex_);
00244     bool success_to_update = computeMidCoords(event.current_real);
00245     if (support_status_ == AIR || support_status_ == BOTH_GROUND) {
00246       publishState("ground");
00247     }
00248     else {
00249       if (support_status_ == LLEG_GROUND) {
00250         publishState("lfoot");
00251       }
00252       else if (support_status_ == RLEG_GROUND) {
00253         publishState("rfoot");
00254       }
00255     }
00256     //if (success_to_update) {
00257     tf::StampedTransform root_transform;
00258     try {
00259       // tf_listener_->lookupTransform(parent_frame_id_, root_frame_id_, event.current_real, root_transform);
00260       // root_link_pose_.setOrigin(root_transform.getOrigin());
00261       // root_link_pose_.setRotation(root_transform.getRotation());
00262     }
00263     catch (tf2::ConnectivityException &e) {
00264       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00265     }
00266     catch (tf2::InvalidArgumentException &e) {
00267       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00268     }
00269     catch (tf2::ExtrapolationException &e) {
00270       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00271     }
00272     catch (tf2::LookupException &e) {
00273       ROS_ERROR("[Footcoords::resolveForceTf] transform error: %s", e.what());
00274     }
00275       //}
00276 
00277       // midcoords is a center coordinates of two feet
00278       // compute root_link -> midcoords
00279       // root_link_pose_ := odom -> root_link
00280       // midcoords_ := odom -> midcoords
00281       // root_link_pose_ * T = midcoords_
00282       // T = root_link_pose_^-1 * midcoords_
00283     //ground_transform_ = root_link_pose_.inverse() * midcoords_;
00284     ground_transform_ = midcoords_;
00285       publishTF(event.current_real);
00286       diagnostic_updater_->update();
00287       publishContactState(event.current_real);
00288   }
00289 
00290   void Footcoords::synchronizeForces(const geometry_msgs::WrenchStamped::ConstPtr& lfoot,
00291                                      const geometry_msgs::WrenchStamped::ConstPtr& rfoot,
00292                                      const sensor_msgs::JointState::ConstPtr& joint_states,
00293                                      const geometry_msgs::PointStamped::ConstPtr& zmp)
00294   {
00295     jsk_footstep_controller::SynchronizedForces forces;
00296     forces.header = lfoot->header;
00297     forces.lleg_force = *lfoot;
00298     forces.rleg_force = *rfoot;
00299     forces.joint_angles = *joint_states;
00300     forces.zmp = *zmp;
00301     pub_synchronized_forces_.publish(forces);
00302     Eigen::Vector3d zmp_point;
00303     tf::pointMsgToEigen(zmp->point, zmp_point);
00304     // Just for visualization
00305     if (zmp->point.z < 0) {
00306       geometry_msgs::TransformStamped ros_zmp_coords;
00307       ros_zmp_coords.header = zmp->header;
00308       ros_zmp_coords.child_frame_id = zmp_frame_id_;
00309       Eigen::Affine3d zmp_pose = Eigen::Affine3d::Identity() * Eigen::Translation3d(zmp_point);        
00310       tf::transformEigenToMsg(zmp_pose, ros_zmp_coords.transform);
00311       std::vector<geometry_msgs::TransformStamped> tf_transforms;
00312       tf_transforms.push_back(ros_zmp_coords);
00313       {
00314         boost::mutex::scoped_lock lock(mutex_);
00315         tf_broadcaster_.sendTransform(tf_transforms);
00316       }
00317     }
00318   }
00319   
00320   void Footcoords::updateChain(std::map<std::string, double>& joint_angles,
00321                                KDL::Chain& chain,
00322                                tf::Pose& output_pose)
00323   {
00324     KDL::JntArray jnt_pos(chain.getNrOfJoints());
00325     for (int i = 0, j = 0; i < chain.getNrOfSegments(); i++) {
00326       /*
00327        * if (chain.getSegment(i).getJoint().getType() == KDL::Joint::None)
00328        *   continue;
00329        */
00330       std::string joint_name = chain.getSegment(i).getJoint().getName();
00331       if (joint_angles.find(joint_name) != joint_angles.end()) {
00332         jnt_pos(j++) = joint_angles[joint_name];
00333       }
00334     }
00335     KDL::ChainFkSolverPos_recursive fk_solver(chain);
00336     KDL::Frame pose;
00337     if (fk_solver.JntToCart(jnt_pos, pose) < 0) {
00338       ROS_FATAL("Failed to compute FK");
00339     }
00340     tf::poseKDLToTF(pose, output_pose);
00341   }
00342 
00343   void Footcoords::updateRobotModel(std::map<std::string, double>& joint_angles)
00344   {
00345 
00346     updateChain(joint_angles, lfoot_chain_, lfoot_pose_);
00347     updateChain(joint_angles, rfoot_chain_, rfoot_pose_);
00348     geometry_msgs::Pose ros_lfoot_pose, ros_rfoot_pose;
00349     tf::poseTFToMsg(lfoot_pose_, ros_lfoot_pose);
00350     tf::poseTFToMsg(rfoot_pose_, ros_rfoot_pose);
00351     pub_debug_lfoot_pos_.publish(ros_lfoot_pose);
00352     pub_debug_rfoot_pos_.publish(ros_rfoot_pose);
00353   }
00354 
00355   void Footcoords::computeVelicity(double dt,
00356                                    std::map<std::string, double>& joint_angles,
00357                                    KDL::Chain& chain,
00358                                    geometry_msgs::Twist& output)
00359   {
00360     KDL::ChainFkSolverVel_recursive fk_solver(chain);
00361     KDL::JntArrayVel jnt_pos(chain.getNrOfJoints());
00362     KDL::JntArray q(chain.getNrOfJoints()), qdot(chain.getNrOfJoints());
00363     for (int i = 0, j = 0; i < chain.getNrOfSegments(); i++) {
00364       std::string joint_name = chain.getSegment(i).getJoint().getName();
00365       if (joint_angles.find(joint_name) != joint_angles.end()) {
00366         qdot(j) = (joint_angles[joint_name] - prev_joints_[joint_name]) / dt;
00367         q(j++) = joint_angles[joint_name];
00368       }
00369     }
00370     jnt_pos.q = q;
00371     jnt_pos.qdot = qdot;
00372     KDL::FrameVel vel;
00373     if (fk_solver.JntToCart(jnt_pos, vel) < 0) {
00374       ROS_FATAL("Failed to compute velocity");
00375     }
00376     KDL::Twist twist = vel.GetTwist();
00377     tf::twistKDLToMsg(twist, output);
00378   }
00379 
00380   void Footcoords::estimateVelocity(const ros::Time& stamp, std::map<std::string, double>& joint_angles)
00381   {
00382     geometry_msgs::TwistStamped twist_stamped;
00383     if (!prev_joints_.empty()) {
00384       double dt = (stamp - last_time_).toSec();
00385       if (odom_status_ == LLEG_SUPPORT || odom_status_ == INITIALIZING) {
00386         computeVelicity(dt, joint_angles, lfoot_chain_, twist_stamped.twist);
00387       }
00388       else if (odom_status_ == RLEG_SUPPORT) {
00389         computeVelicity(dt, joint_angles, rfoot_chain_, twist_stamped.twist);
00390       }
00391       twist_stamped.header.stamp = stamp;
00392       twist_stamped.header.frame_id = root_frame_id_;
00393       pub_twist_.publish(twist_stamped);
00394     }
00395   }
00396 
00397   void Footcoords::filter(const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg)
00398   {
00399     boost::mutex::scoped_lock lock(mutex_);
00400     geometry_msgs::WrenchStamped lfoot = msg->lleg_force;
00401     geometry_msgs::WrenchStamped rfoot = msg->rleg_force;
00402     zmp_ = Eigen::Vector3f(msg->zmp.point.x, msg->zmp.point.y, msg->zmp.point.z);
00403     sensor_msgs::JointState joint_angles = msg->joint_angles;
00404     std::map<std::string, double> angles;
00405     for (size_t i = 0; i < joint_angles.name.size(); i++) {
00406       angles[joint_angles.name[i]] = joint_angles.position[i];
00407     }
00408 
00409     updateRobotModel(angles);
00410 
00411     // lowpass filter
00412     tf::Vector3 lfoot_force_vector, rfoot_force_vector;
00413     if (!resolveForceTf(lfoot, rfoot, lfoot_force_vector, rfoot_force_vector)) {
00414       ROS_ERROR("[Footcoords::filter] failed to resolve tf of force sensor");
00415       return;
00416     }
00417     // resolve tf
00418     double lfoot_force = applyLowPassFilter(lfoot_force_vector[2], prev_lforce_);
00419     double rfoot_force = applyLowPassFilter(rfoot_force_vector[2], prev_rforce_);
00420 
00421     // publish lowlevel info
00422     FootCoordsLowLevelInfo info;
00423     info.header = lfoot.header;
00424     info.raw_lleg_force = lfoot_force_vector[2];
00425     info.raw_rleg_force = rfoot_force_vector[2];
00426     info.filtered_lleg_force = lfoot_force;
00427     info.filtered_rleg_force = rfoot_force;
00428     info.threshold = force_thr_;
00429     pub_low_level_.publish(info);
00430     prev_lforce_ = lfoot_force;
00431     prev_rforce_ = rfoot_force;
00432 
00433     if (lfoot_force >= force_thr_ && rfoot_force >= force_thr_) {
00434       support_status_ = BOTH_GROUND;
00435     }
00436     else if (lfoot_force < force_thr_ && rfoot_force < force_thr_) {
00437       support_status_ = AIR;
00438     }
00439     else if (lfoot_force >= force_thr_) {
00440       // only left
00441       support_status_ = LLEG_GROUND;
00442     }
00443     else if (rfoot_force >= force_thr_) {
00444       // only right
00445       support_status_ = RLEG_GROUND;
00446     }
00447     estimateOdometry();
00448     estimateVelocity(msg->header.stamp, angles);
00449     geometry_msgs::PoseStamped leg_odometory;
00450     leg_odometory.header.stamp = msg->header.stamp;
00451     leg_odometory.header.frame_id = root_frame_id_;
00452     tf::poseTFToMsg(estimated_odom_pose_, leg_odometory.pose);
00453     pub_leg_odometory_.publish(leg_odometory);
00454     /* tf for debug*/
00455     std::vector<geometry_msgs::TransformStamped> tf_transforms;
00456     geometry_msgs::TransformStamped odom_transform;
00457     tf::transformTFToMsg(estimated_odom_pose_, odom_transform.transform);
00458     odom_transform.header = leg_odometory.header;
00459     odom_transform.child_frame_id = "leg_odom";
00460     tf_transforms.push_back(odom_transform);
00461     tf_broadcaster_.sendTransform(tf_transforms);
00462     prev_joints_ = angles;
00463     last_time_ = msg->header.stamp;
00464   }
00465 
00466   void Footcoords::estimateOdometry()
00467   {
00468     //estimateOdometryMainSupportLeg();
00469     estimateOdometryZMPSupportLeg();
00470   }
00471 
00472   void Footcoords::estimateOdometryNaive()
00473   {
00474     if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
00475       ROS_INFO("changed to INITIALIZING");
00476       odom_status_ = INITIALIZING;
00477     }
00478     if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
00479       ROS_INFO_THROTTLE(1.0, "INITIALIZING");
00480       /* Update odom origin */
00481       tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().slerp(rfoot_pose_.getRotation(), 0.5);
00482       tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
00483       tf::Pose midcoords;
00484       midcoords.setOrigin(midcoords_pos);
00485       midcoords.setRotation(midcoords_rot);
00486       lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
00487       rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
00488       estimated_odom_pose_ = midcoords;
00489     }
00490     if (odom_status_ == INITIALIZING && support_status_ ==RLEG_GROUND) {
00491       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00492       odom_status_ = RLEG_SUPPORT;
00493       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00494     }
00495     else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
00496       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00497       odom_status_ = LLEG_SUPPORT;
00498       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00499     }
00500     else if (odom_status_ == RLEG_SUPPORT && support_status_ == RLEG_GROUND) {
00501       ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
00502       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00503     }
00504     else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00505       ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
00506       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00507       lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
00508     }
00509     else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00510       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00511       odom_status_ = LLEG_SUPPORT;
00512       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00513     }
00514     else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00515       ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
00516       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00517     }
00518     else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00519       ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
00520       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00521       rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
00522     }
00523     else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
00524       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00525       odom_status_ = RLEG_SUPPORT;
00526       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00527     }
00528     if (support_status_ == AIR) {
00529       ROS_INFO_THROTTLE(1.0, "resetting");
00530       odom_status_ = UNINITIALIZED;
00531     }
00532   }
00533 
00534   void Footcoords::estimateOdometryMainSupportLeg()
00535   {
00536     if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
00537       ROS_INFO("changed to INITIALIZING");
00538       odom_status_ = INITIALIZING;
00539     }
00540     if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
00541       ROS_INFO_THROTTLE(1.0, "INITIALIZING");
00542       /* Update odom origin */
00543       tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().slerp(rfoot_pose_.getRotation(), 0.5);
00544       tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
00545       tf::Pose midcoords;
00546       midcoords.setOrigin(midcoords_pos);
00547       midcoords.setRotation(midcoords_rot);
00548       lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
00549       rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
00550       estimated_odom_pose_ = midcoords;
00551     }
00552     if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
00553       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00554       odom_status_ = RLEG_SUPPORT;
00555       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00556     }
00557     else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
00558       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00559       odom_status_ = LLEG_SUPPORT;
00560       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00561     }
00562     else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
00563       ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
00564       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00565     }
00566     else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00567       if (prev_lforce_ > prev_rforce_) {
00568         /* switch to lleg */
00569         odom_status_ = LLEG_SUPPORT;
00570         ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to lleg");
00571         estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00572         rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
00573       }
00574       else {
00575         ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
00576         estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00577         lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
00578       }
00579     }
00580     else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00581       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00582       odom_status_ = LLEG_SUPPORT;
00583       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00584     }
00585     else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00586       ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
00587       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00588     }
00589     else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00590       if (prev_rforce_ > prev_lforce_) {
00591         odom_status_ = RLEG_SUPPORT;
00592         ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to rleg");
00593         estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00594         lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
00595       }
00596       else {
00597         ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
00598         estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00599         rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
00600       }
00601     }
00602     else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
00603       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00604       odom_status_ = RLEG_SUPPORT;
00605       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00606     }
00607     if (support_status_ == AIR) {
00608       ROS_INFO_THROTTLE(1.0, "resetting");
00609       odom_status_ = UNINITIALIZED;
00610     }
00611   }
00612 
00613     void Footcoords::estimateOdometryZMPSupportLeg()
00614   {
00615     if (odom_status_ == UNINITIALIZED && support_status_ == BOTH_GROUND) {
00616       ROS_INFO("changed to INITIALIZING");
00617       odom_status_ = INITIALIZING;
00618     }
00619     if (odom_status_ == INITIALIZING && support_status_ == BOTH_GROUND) {
00620       ROS_INFO_THROTTLE(1.0, "INITIALIZING");
00621       /* Update odom origin */
00622       tf::Quaternion midcoords_rot = lfoot_pose_.getRotation().slerp(rfoot_pose_.getRotation(), 0.5);
00623       tf::Vector3 midcoords_pos = lfoot_pose_.getOrigin().lerp(rfoot_pose_.getOrigin(), 0.5);
00624       tf::Pose midcoords;
00625       midcoords.setOrigin(midcoords_pos);
00626       midcoords.setRotation(midcoords_rot);
00627       lfoot_to_origin_pose_ = lfoot_pose_.inverse() * midcoords;
00628       rfoot_to_origin_pose_ = rfoot_pose_.inverse() * midcoords;
00629       estimated_odom_pose_ = midcoords;
00630     }
00631     if (odom_status_ == INITIALIZING && support_status_ == RLEG_GROUND) {
00632       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00633       odom_status_ = RLEG_SUPPORT;
00634       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00635     }
00636     else if (odom_status_ == INITIALIZING && support_status_ == LLEG_GROUND) {
00637       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00638       odom_status_ = LLEG_SUPPORT;
00639       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00640     }
00641     else if (odom_status_ == RLEG_SUPPORT && support_status_ ==RLEG_GROUND) {
00642       ROS_INFO_THROTTLE(1.0, "keep RLEG support phase");
00643       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00644     }
00645     else if (odom_status_ == RLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00646       if (zmp_[1] > 0) {
00647         /* switch to lleg */
00648         odom_status_ = LLEG_SUPPORT;
00649         ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to lleg");
00650         estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00651         rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
00652       }
00653       else {
00654         ROS_INFO_THROTTLE(1.0, "dual leg support phase but use RLEG");
00655         estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00656         lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
00657       }
00658     }
00659     else if (odom_status_ == RLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00660       ROS_INFO_THROTTLE(1.0, "detect LLEG support phase");
00661       odom_status_ = LLEG_SUPPORT;
00662       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;
00663     }
00664     else if (odom_status_ == LLEG_SUPPORT && support_status_ == LLEG_GROUND) {
00665       ROS_INFO_THROTTLE(1.0, "keep LLEG support phase");
00666       estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00667     }
00668     else if (odom_status_ == LLEG_SUPPORT && support_status_ == BOTH_GROUND) {
00669       if (zmp_[1] < 0) {
00670         odom_status_ = RLEG_SUPPORT;
00671         ROS_INFO_THROTTLE(1.0, "dual leg support phase, switch to rleg");
00672         estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00673         lfoot_to_origin_pose_ = lfoot_pose_.inverse() * rfoot_pose_ * rfoot_to_origin_pose_;
00674       }
00675       else {
00676         ROS_INFO_THROTTLE(1.0, "dual leg support phase but use LLEG");
00677         estimated_odom_pose_ = lfoot_pose_ * lfoot_to_origin_pose_;;
00678         rfoot_to_origin_pose_ = rfoot_pose_.inverse() * lfoot_pose_ * lfoot_to_origin_pose_;
00679       }
00680     }
00681     else if (odom_status_ == LLEG_SUPPORT && support_status_ == RLEG_GROUND) {
00682       ROS_INFO_THROTTLE(1.0, "detect RLEG support phase");
00683       odom_status_ = RLEG_SUPPORT;
00684       estimated_odom_pose_ = rfoot_pose_ * rfoot_to_origin_pose_;
00685     }
00686     if (support_status_ == AIR) {
00687       ROS_INFO_THROTTLE(1.0, "resetting");
00688       odom_status_ = UNINITIALIZED;
00689     }
00690   }
00691 
00692 
00693 
00694   void Footcoords::publishState(const std::string& state)
00695   {
00696     std_msgs::String state_msg;
00697     state_msg.data = state;
00698     pub_state_.publish(state_msg);
00699   }
00700   
00701   void Footcoords::publishContactState(const ros::Time& stamp)
00702   {
00703     GroundContactState contact_state;
00704     contact_state.header.stamp = stamp;
00705     if (support_status_ == AIR) {
00706       contact_state.contact_state
00707         = GroundContactState::CONTACT_AIR;
00708     }
00709     else if (support_status_ == LLEG_GROUND) {
00710       contact_state.contact_state 
00711         = GroundContactState::CONTACT_LLEG_GROUND;
00712     }
00713     else if (support_status_ == RLEG_GROUND) {
00714       contact_state.contact_state 
00715         = GroundContactState::CONTACT_RLEG_GROUND;
00716     }
00717     else if (support_status_ == BOTH_GROUND) {
00718       contact_state.contact_state
00719         = GroundContactState::CONTACT_BOTH_GROUND;
00720     }
00721     try 
00722     {
00723       tf::StampedTransform foot_transform;
00724       tf_listener_->lookupTransform(
00725         lfoot_frame_id_, rfoot_frame_id_, stamp, foot_transform);
00726       double roll, pitch, yaw;
00727       foot_transform.getBasis().getRPY(roll, pitch, yaw);
00728       contact_state.error_pitch_angle = std::abs(pitch);
00729       contact_state.error_roll_angle = std::abs(roll);
00730       contact_state.error_yaw_angle = std::abs(yaw);
00731       contact_state.error_z = std::abs(foot_transform.getOrigin().z());
00732       pub_contact_state_.publish(contact_state);
00733     }
00734     catch (tf2::ConnectivityException &e)
00735     {
00736       ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
00737     }
00738     catch (tf2::InvalidArgumentException &e)
00739     {
00740       ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
00741     }
00742     catch (tf2::ExtrapolationException &e)
00743     {
00744       ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
00745     }
00746     catch (tf2::LookupException &e)
00747     {
00748       ROS_ERROR("[Footcoords::publishContactState] transform error: %s", e.what());
00749     }
00750 
00751   }
00752 
00753   bool Footcoords::computeMidCoordsFromSingleLeg(const ros::Time& stamp,
00754                                                  bool use_left_leg)
00755   {
00756     if (!waitForEndEffectorTrasnformation(stamp)) {
00757       ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] Failed to lookup endeffector transformation");
00758       return false;
00759     }
00760     else {
00761       try
00762       {
00763         tf::StampedTransform foot_transform; // parent -> foot
00764         if (use_left_leg) {     // left on the ground
00765           tf_listener_->lookupTransform(
00766             root_frame_id_, lfoot_frame_id_, stamp, foot_transform);
00767         }
00768         else {                  // right on the ground
00769           tf_listener_->lookupTransform(
00770             root_frame_id_, rfoot_frame_id_, stamp, foot_transform);
00771         }
00772         midcoords_ = foot_transform.inverse();
00773         return true;
00774       }
00775       catch (tf2::ConnectivityException &e)
00776       {
00777         ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
00778         return false;
00779       }
00780       catch (tf2::InvalidArgumentException &e)
00781       {
00782         ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
00783         return false;
00784       }
00785       catch (tf2::ExtrapolationException &e)
00786       {
00787         ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
00788       }
00789       catch (tf2::LookupException &e)
00790       {
00791         ROS_ERROR("[Footcoords::computeMidCoordsFromSingleLeg] transform error: %s", e.what());
00792       }
00793 
00794 
00795     }
00796   }
00797   
00798   bool Footcoords::computeMidCoords(const ros::Time& stamp)
00799   {
00800     if (!waitForEndEffectorTrasnformation(stamp)) {
00801       ROS_ERROR("[Footcoords::computeMidCoords] Failed to lookup endeffector transformation");
00802       return false;
00803     }
00804     else {
00805       try 
00806       {
00807         tf::StampedTransform lfoot_transform;
00808         tf_listener_->lookupTransform(
00809           root_frame_id_, lfoot_frame_id_, stamp, lfoot_transform);
00810         tf::StampedTransform rfoot_transform;
00811         tf_listener_->lookupTransform(
00812           root_frame_id_, rfoot_frame_id_, stamp, rfoot_transform);
00813         tf::Quaternion lfoot_rot = lfoot_transform.getRotation();
00814         tf::Quaternion rfoot_rot = rfoot_transform.getRotation();
00815         tf::Quaternion mid_rot = lfoot_rot.slerp(rfoot_rot, 0.5);
00816         tf::Vector3 lfoot_pos = lfoot_transform.getOrigin();
00817         tf::Vector3 rfoot_pos = rfoot_transform.getOrigin();
00818         tf::Vector3 mid_pos = lfoot_pos.lerp(rfoot_pos, 0.5);
00819         midcoords_.setOrigin(mid_pos);
00820         midcoords_.setRotation(mid_rot);
00821         midcoords_ = midcoords_;
00822         return true;
00823       }
00824       catch (tf2::ConnectivityException &e)
00825       {
00826         ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
00827         return false;
00828       }
00829       catch (tf2::InvalidArgumentException &e)
00830       {
00831         ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
00832         return false;
00833       }
00834       catch (tf2::ExtrapolationException &e)
00835       {
00836         ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
00837       }
00838       catch (tf2::LookupException &e)
00839       {
00840         ROS_ERROR("[Footcoords::computeMidCoords] transform error: %s", e.what());
00841       }
00842 
00843     }
00844   }
00845 
00846   bool Footcoords::waitForSensorFrameTransformation(const ros::Time& stamp,
00847                                                    const std::string& lsensor_frame,
00848                                                    const std::string& rsensor_frame)
00849   {
00850     // lfsensor -> lleg_end_coords
00851     if (!tf_listener_->waitForTransform(
00852           lsensor_frame, lfoot_sensor_frame_, stamp, ros::Duration(1.0))) {
00853       ROS_ERROR("[Footcoords::waitForSensorFrameTransformation] failed to lookup transform between %s and %s",
00854                 lsensor_frame.c_str(),
00855                 lfoot_sensor_frame_.c_str());
00856       return false;
00857     }
00858     if (!tf_listener_->waitForTransform(
00859           rsensor_frame, rfoot_sensor_frame_, stamp, ros::Duration(1.0))) {
00860       ROS_ERROR("[Footcoords::waitForSensorFrameTransformation] failed to lookup transform between %s and %s",
00861                 rsensor_frame.c_str(),
00862                 rfoot_sensor_frame_.c_str());
00863       return false;
00864     }
00865     return true;
00866   }
00867 
00868   bool Footcoords::waitForEndEffectorTrasnformation(const ros::Time& stamp)
00869   {
00870     // odom -> lfoot
00871     if (!tf_listener_->waitForTransform(
00872           root_frame_id_, lfoot_frame_id_, stamp, ros::Duration(1.0))) {
00873       ROS_ERROR("[Footcoords::waitForEndEffectorTrasnformation] failed to lookup transform between %s and %s",
00874                 root_frame_id_.c_str(),
00875                 lfoot_frame_id_.c_str());
00876       return false;
00877     }
00878     // odom -> rfoot
00879     else if (!tf_listener_->waitForTransform(
00880                root_frame_id_, rfoot_frame_id_, stamp, ros::Duration(1.0))) {
00881       ROS_ERROR("[Footcoords::waitForEndEffectorTrasnformation]failed to lookup transform between %s and %s",
00882                 root_frame_id_.c_str(),
00883                 rfoot_frame_id_.c_str());
00884       return false;
00885     }
00886     // lfoot -> rfoot
00887     else if (!tf_listener_->waitForTransform(
00888                lfoot_frame_id_, rfoot_frame_id_, stamp, ros::Duration(1.0))) {
00889       ROS_ERROR("[Footcoords::waitForEndEffectorTrasnformation]failed to lookup transform between %s and %s",
00890                 lfoot_frame_id_.c_str(),
00891                 rfoot_frame_id_.c_str());
00892       return false;
00893     }
00894     return true;
00895   }
00896 
00897   bool Footcoords::updateGroundTF()
00898   {
00899     // project `/odom` on the plane of midcoords_
00900     // odom -> midcoords is available as `midcoords_`
00901     // we need odom -> odom_on_ground
00902     // 1. in order to get translation,
00903     //    project odom point to
00904     if (false && support_status_ == BOTH_GROUND) {
00905       // use locked_midcoords_to_odom_on_ground_ during dual stance phase
00906       ground_transform_ = midcoords_ * locked_midcoords_to_odom_on_ground_;
00907     }
00908     else {
00909       Eigen::Affine3d odom_to_midcoords;
00910       tf::transformTFToEigen(midcoords_, odom_to_midcoords);
00911       Eigen::Affine3d midcoords_to_odom = odom_to_midcoords.inverse();
00912       Eigen::Affine3d midcoords_to_odom_on_ground = midcoords_to_odom;
00913       midcoords_to_odom_on_ground.translation().z() = 0.0;
00914       Eigen::Vector3d zaxis;
00915       zaxis[0] = midcoords_to_odom_on_ground(0, 2);
00916       zaxis[1] = midcoords_to_odom_on_ground(1, 2);
00917       zaxis[2] = midcoords_to_odom_on_ground(2, 2);
00918       Eigen::Quaterniond rot;
00919       rot.setFromTwoVectors(zaxis, Eigen::Vector3d(0, 0, 1));
00920       midcoords_to_odom_on_ground.rotate(rot);
00921       Eigen::Affine3d odom_to_odom_on_ground
00922         = odom_to_midcoords * midcoords_to_odom_on_ground;
00923       tf::transformEigenToTF(odom_to_odom_on_ground,
00924                              ground_transform_);
00925     }
00926   }
00927 
00928   void Footcoords::getRollPitch(const Eigen::Affine3d& pose, float& roll, float& pitch)
00929   {
00930     Eigen::Affine3f posef;
00931     jsk_pcl_ros::convertEigenAffine3(pose, posef);
00932     float yaw;
00933     pcl::getEulerAngles(posef, roll, pitch, yaw);
00934   }
00935 
00936   float Footcoords::getYaw(const Eigen::Affine3d& pose)
00937   {
00938     Eigen::Affine3f posef;
00939     jsk_pcl_ros::convertEigenAffine3(pose, posef);
00940     float roll, pitch, yaw;
00941     pcl::getEulerAngles(posef, roll, pitch, yaw);
00942     return yaw;
00943   }
00944 
00945   void Footcoords::publishTF(const ros::Time& stamp)
00946   {
00947     // publish midcoords_ and ground_cooords_
00948     geometry_msgs::TransformStamped ros_midcoords, 
00949       ros_ground_coords, ros_odom_to_body_coords,
00950       ros_body_on_odom_coords, ros_odom_init_coords;
00951     // ros_midcoords: ROOT -> ground
00952     // ros_ground_coords: odom -> odom_on_ground = identity
00953     // ros_odom_root_coords: odom -> odom_root = identity
00954     // ros_ground_coords: odom_root -> odom_on_ground = identity
00955     std_msgs::Header header;
00956     header.stamp = stamp;
00957     header.frame_id = parent_frame_id_;
00958     ros_midcoords.header.stamp = stamp;
00959     ros_midcoords.header.frame_id = root_frame_id_;
00960     ros_midcoords.child_frame_id = midcoords_frame_id_;
00961     ros_ground_coords.header.stamp = stamp;
00962     ros_ground_coords.header.frame_id = parent_frame_id_;
00963     ros_ground_coords.child_frame_id = output_frame_id_;
00964     ros_odom_to_body_coords.header.stamp = stamp;
00965     ros_odom_to_body_coords.header.frame_id = parent_frame_id_;
00966     ros_odom_to_body_coords.child_frame_id = root_frame_id_;
00967     ros_body_on_odom_coords.header.stamp = stamp;
00968     ros_body_on_odom_coords.header.frame_id = root_frame_id_;
00969     ros_body_on_odom_coords.child_frame_id = body_on_odom_frame_;
00970     ros_odom_init_coords.header.stamp = stamp;
00971     ros_odom_init_coords.header.frame_id = parent_frame_id_;
00972     ros_odom_init_coords.child_frame_id = odom_init_frame_id_;
00973     Eigen::Affine3d identity = Eigen::Affine3d::Identity();
00974     float roll, pitch;
00975     getRollPitch(odom_pose_, roll, pitch);
00976     Eigen::Affine3d body_on_odom_pose = (Eigen::Translation3d(0,
00977                                                               0,
00978                                                               odom_pose_.translation()[2]) * 
00979                                          Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX()) *
00980                                          Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()));
00981     midcoords_.getRotation().normalize();
00982     Eigen::Affine3d odom_init_pose = (Eigen::Translation3d(odom_init_pose_.translation()[0],
00983                                                            odom_init_pose_.translation()[1],
00984                                                            0.0) * 
00985                                       Eigen::AngleAxisd(getYaw(odom_init_pose_), Eigen::Vector3d::UnitZ()));
00986 
00987     tf::transformTFToMsg(midcoords_, ros_midcoords.transform);
00988     tf::transformEigenToMsg(identity, ros_ground_coords.transform);
00989     tf::transformEigenToMsg(body_on_odom_pose.inverse(), ros_body_on_odom_coords.transform);
00990     tf::transformEigenToMsg(odom_pose_, ros_odom_to_body_coords.transform);
00991     tf::transformEigenToMsg(odom_init_pose, ros_odom_init_coords.transform);
00992     std::vector<geometry_msgs::TransformStamped> tf_transforms;
00993     tf_transforms.push_back(ros_midcoords);
00994     tf_transforms.push_back(ros_ground_coords);
00995     tf_transforms.push_back(ros_odom_to_body_coords);
00996     tf_transforms.push_back(ros_body_on_odom_coords);
00997     tf_transforms.push_back(ros_odom_init_coords);
00998     tf_broadcaster_.sendTransform(tf_transforms);
00999   }
01000 
01001   void Footcoords::odomInitTriggerCallback(const std_msgs::Empty& trigger)
01002   {
01003     boost::mutex::scoped_lock lock(mutex_);
01004     // Update odom_init_pose
01005     odom_init_pose_ = odom_pose_;
01006   }
01007 
01008   void Footcoords::odomImuCallback(const nav_msgs::Odometry::ConstPtr& odom_msg,
01009                                    const sensor_msgs::Imu::ConstPtr& imu_msg)
01010   {
01011     boost::mutex::scoped_lock lock(mutex_);
01012     if (use_imu_) {
01013       Eigen::Affine3d odom_pose;
01014       tf::poseMsgToEigen(odom_msg->pose.pose, odom_pose);
01015       Eigen::Quaterniond imu_orientation;
01016       tf::quaternionMsgToEigen(imu_msg->orientation, imu_orientation);
01017       if (use_imu_yaw_) {
01018         odom_pose_ = Eigen::Translation3d(odom_pose.translation()) * imu_orientation;
01019       }
01020       else {
01021         float roll, pitch;
01022         getRollPitch(Eigen::Affine3d::Identity() * imu_orientation, roll, pitch);
01023         odom_pose_ = (Eigen::Translation3d(odom_pose.translation()) *
01024                       Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX()) *
01025                       Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()));
01026       }
01027     }
01028     else {
01029       tf::poseMsgToEigen(odom_msg->pose.pose, odom_pose_);
01030     }
01031   }
01032 }
01033 
01034 int main(int argc, char** argv)
01035 {
01036   ros::init(argc, argv, "footcoords");
01037   jsk_footstep_controller::Footcoords c;
01038   ros::spin();
01039 }


jsk_footstep_controller
Author(s):
autogenerated on Wed Sep 16 2015 04:38:12