pr2_point_frame.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <vector>
00038 #include <boost/scoped_ptr.hpp>
00039 #include <boost/thread/condition.hpp>
00040 
00041 #include <actionlib/server/action_server.h>
00042 #include <geometry_msgs/PoseStamped.h>
00043 #include <geometry_msgs/PointStamped.h>
00044 #include <geometry_msgs/Twist.h>
00045 
00046 #include <kdl/chainfksolver.hpp>
00047 #include <kdl/chain.hpp>
00048 #include <kdl/chainjnttojacsolver.hpp>
00049 #include <kdl/frames.hpp>
00050 #include "kdl/chainfksolverpos_recursive.hpp"
00051 #include "kdl_parser/kdl_parser.hpp"
00052 
00053 #include "tf_conversions/tf_kdl.h"
00054 #include <message_filters/subscriber.h>
00055 #include <tf/message_filter.h>
00056 #include <tf/transform_datatypes.h>
00057 #include <tf/transform_listener.h>
00058 
00059 #include <sensor_msgs/JointState.h>
00060 #include <std_msgs/Float32MultiArray.h>
00061 #include <std_msgs/Int32.h>
00062 
00063 #include <urdf/model.h>
00064 
00065 #include <trajectory_msgs/JointTrajectory.h>
00066 #include <pr2_controllers_msgs/PointHeadAction.h>
00067 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
00068 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
00069 
00070 
00071 void printVector3(const char * label, tf::Vector3 v)
00072 {
00073   printf("%s % 7.3f % 7.3f % 7.3f\n", label, v.x(), v.y(), v.z() );
00074 
00075 }
00076 
00077 class ControlHead
00078 {
00079 private:
00080   typedef actionlib::ActionServer<pr2_controllers_msgs::PointHeadAction> PHAS;
00081   typedef PHAS::GoalHandle GoalHandle;
00082 
00083   std::string node_name_;
00084   std::string action_name_;
00085   std::string root_;
00086   std::string tip_;
00087   std::string pan_link_;
00088   std::string default_pointing_frame_;
00089   std::string pointing_frame_;
00090   tf::Vector3 pointing_axis_;
00091   std::vector< std::string> joint_names_;
00092 
00093   ros::NodeHandle nh_, pnh_;
00094   ros::Publisher pub_controller_command_;
00095   ros::Subscriber sub_controller_state_;
00096   ros::Subscriber command_sub_;
00097   ros::ServiceClient cli_query_traj_;
00098   ros::Timer watchdog_timer_;
00099 
00100   PHAS action_server_;
00101   bool has_active_goal_;
00102   GoalHandle active_goal_;
00103   tf::Stamped<tf::Point> target_in_pan_;
00104   std::string pan_parent_;
00105   double success_angle_threshold_;
00106 
00107   geometry_msgs::PointStamped target_;
00108   KDL::Tree tree_;
00109   KDL::Chain chain_;
00110   tf::Point target_in_root_;
00111 
00112   boost::scoped_ptr<KDL::ChainFkSolverPos> pose_solver_;
00113   boost::scoped_ptr<KDL::ChainJntToJacSolver> jac_solver_;
00114 
00115   tf::TransformListener tfl_;
00116   urdf::Model urdf_model_;
00117 
00118 public:
00119 
00120   ControlHead(const ros::NodeHandle &node) :
00121       node_name_(ros::this_node::getName())
00122       , action_name_("point_head_action")
00123       , nh_(node)
00124       , pnh_("~")
00125       , action_server_(nh_, action_name_.c_str(),
00126                          boost::bind(&ControlHead::goalCB, this, _1),
00127                          boost::bind(&ControlHead::cancelCB, this, _1), false)
00128       , has_active_goal_(false)
00129   {
00130     pnh_.param("pan_link", pan_link_, std::string("head_pan_link"));
00131     pnh_.param("default_pointing_frame", default_pointing_frame_, std::string("head_tilt_link"));
00132     pnh_.param("success_angle_threshold", success_angle_threshold_, 0.1);
00133 
00134     if(pan_link_[0] == '/') pan_link_.erase(0, 1);
00135     if(default_pointing_frame_[0] == '/') default_pointing_frame_.erase(0, 1);
00136 
00137     // Connects to the controller
00138     pub_controller_command_ =
00139       nh_.advertise<trajectory_msgs::JointTrajectory>("command", 2);
00140     sub_controller_state_ =
00141       nh_.subscribe("state", 1, &ControlHead::controllerStateCB, this);
00142     cli_query_traj_ =
00143         nh_.serviceClient<pr2_controllers_msgs::QueryTrajectoryState>("/head_traj_controller/query_state");
00144 
00145     // Should only ever happen on first call... move to constructor?
00146     if(tree_.getNrOfJoints() == 0)
00147     {
00148       std::string robot_desc_string;
00149       nh_.param("/robot_description", robot_desc_string, std::string());
00150       ROS_DEBUG("Reading tree from robot_description...");
00151       if (!kdl_parser::treeFromString(robot_desc_string, tree_)){
00152          ROS_ERROR("Failed to construct kdl tree");
00153          exit(-1);
00154       }
00155       if (!urdf_model_.initString(robot_desc_string)){
00156         ROS_ERROR("Failed to parse urdf string for urdf::Model.");
00157         exit(-2);
00158       }
00159     }
00160 
00161     ROS_DEBUG("Tree has %d joints and %d segments.", tree_.getNrOfJoints(), tree_.getNrOfSegments());
00162 
00163     action_server_.start();
00164 
00165     watchdog_timer_ = nh_.createTimer(ros::Duration(1.0), &ControlHead::watchdog, this);
00166   }
00167 
00168   void goalCB(GoalHandle gh)
00169   {
00170     // Before we do anything, we need to know that name of the pan_link's parent, which we will treat as the root.
00171     if (root_.empty())
00172     {
00173       for (int i = 0; i < 10; ++i)
00174       {
00175         try {
00176           tfl_.getParent(pan_link_, ros::Time(), root_);
00177           break;
00178         }
00179         catch (const tf::TransformException &ex) {}
00180         ros::Duration(0.5).sleep();
00181       }
00182       if (root_.empty())
00183       {
00184         ROS_ERROR("Could not get parent of %s in the TF tree", pan_link_.c_str());
00185         gh.setRejected();
00186         return;
00187       }
00188     }
00189     if(root_[0] == '/') root_.erase(0, 1);
00190 
00191     ROS_DEBUG("Got point head goal!");
00192 
00193     // Process pointing frame and axis
00194     const geometry_msgs::PointStamped &target = gh.getGoal()->target;
00195     pointing_frame_ = gh.getGoal()->pointing_frame;
00196     if(pointing_frame_.length() == 0)
00197     {
00198       ROS_WARN("Pointing frame not specified, using %s [1, 0, 0] by default.", default_pointing_frame_.c_str());
00199       pointing_frame_ = default_pointing_frame_;
00200       pointing_axis_ = tf::Vector3(1.0, 0.0, 0.0);
00201     }
00202     else
00203     {
00204       if(pointing_frame_[0] == '/') pointing_frame_.erase(0, 1);
00205       bool ret1 = false;
00206       try
00207       {
00208         std::string error_msg;
00209         ret1 = tfl_.waitForTransform(pan_link_, pointing_frame_, target.header.stamp,
00210                                    ros::Duration(5.0), ros::Duration(0.01), &error_msg);
00211 
00212         tf::vector3MsgToTF(gh.getGoal()->pointing_axis, pointing_axis_);
00213         if(pointing_axis_.length() < 0.1)
00214         {
00215           size_t found = pointing_frame_.find("optical_frame");
00216           if (found != std::string::npos)
00217           {
00218             ROS_WARN("Pointing axis appears to be zero-length. Using [0, 0, 1] as default for an optical frame.");
00219             pointing_axis_ = tf::Vector3(0, 0, 1);
00220           }
00221           else
00222           {
00223             ROS_WARN("Pointing axis appears to be zero-length. Using [1, 0, 0] as default for a non-optical frame.");
00224             pointing_axis_ = tf::Vector3(1, 0, 0);
00225           }
00226         }
00227         else
00228         {
00229           pointing_axis_.normalize();
00230         }
00231       }
00232       catch(const tf::TransformException &ex)
00233       {
00234         ROS_ERROR("Transform failure (%d): %s", ret1, ex.what());
00235         gh.setRejected();
00236         return;
00237       }
00238     }
00239 
00240     //Put the target point in the root frame (usually torso_lift_link).
00241     bool ret1 = false;
00242     try
00243     {
00244       std::string error_msg;
00245       ret1 = tfl_.waitForTransform(root_.c_str(), target.header.frame_id, target.header.stamp,
00246                                        ros::Duration(5.0), ros::Duration(0.01), &error_msg);
00247 
00248       geometry_msgs::PointStamped target_in_root_msg;
00249       tfl_.transformPoint(root_.c_str(), target, target_in_root_msg );
00250       tf::pointMsgToTF(target_in_root_msg.point, target_in_root_);
00251     }
00252     catch(const tf::TransformException &ex)
00253     {
00254       ROS_ERROR("Transform failure (%d): %s", ret1, ex.what());
00255       gh.setRejected();
00256       return;
00257     }
00258 
00259     if( tip_.compare(pointing_frame_) != 0 )
00260     {
00261       bool success = tree_.getChain(root_.c_str(), pointing_frame_.c_str(), chain_);
00262       if( !success )
00263       {
00264         ROS_ERROR("Couldn't create chain from %s to %s.", root_.c_str(), pointing_frame_.c_str());
00265         gh.setRejected();
00266         return;
00267       }
00268       tip_ = pointing_frame_;
00269 
00270       pose_solver_.reset(new KDL::ChainFkSolverPos_recursive(chain_));
00271       jac_solver_.reset(new KDL::ChainJntToJacSolver(chain_));
00272       joint_names_.resize(chain_.getNrOfJoints());
00273     }
00274 
00275     unsigned int joints = chain_.getNrOfJoints();
00276 
00277 //    int segments = chain_.getNrOfSegments();
00278 //    ROS_INFO("Parsed urdf from %s to %s and found %d joints and %d segments.", root_.c_str(), pointing_frame_.c_str(), joints, segments);
00279 //    for(int i = 0; i < segments; i++)
00280 //    {
00281 //      KDL::Segment segment = chain_.getSegment(i);
00282 //      ROS_INFO("Segment %d, %s: joint %s type %s",
00283 //               i, segment.getName().c_str(), segment.getJoint().getName().c_str(), segment.getJoint().getTypeName().c_str() );
00284 //    }
00285 
00286     KDL::JntArray jnt_pos(joints), jnt_eff(joints);
00287     KDL::Jacobian jacobian(joints);
00288 
00289     pr2_controllers_msgs::QueryTrajectoryState traj_state;
00290     traj_state.request.time = ros::Time::now() + ros::Duration(0.01);
00291     if (!cli_query_traj_.call(traj_state))
00292     {
00293       ROS_ERROR("Service call to query controller trajectory failed.");
00294       gh.setRejected();
00295       return;
00296     }
00297     if(traj_state.response.name.size() != joints)
00298     {
00299       ROS_ERROR("Number of joints mismatch: urdf chain vs. trajectory controller state.");
00300       gh.setRejected();
00301       return;
00302     }
00303     std::vector<urdf::JointLimits> limits_(joints);
00304 
00305     // Get initial joint positions and joint limits.
00306     for(unsigned int i = 0; i < joints; i++)
00307     {
00308       joint_names_[i] = traj_state.response.name[i];
00309       limits_[i] = *(urdf_model_.joints_[joint_names_[i].c_str()]->limits);
00310       ROS_DEBUG("Joint %d %s: %f, limits: %f %f", i, traj_state.response.name[i].c_str(), traj_state.response.position[i], limits_[i].lower, limits_[i].upper);
00311       //jnt_pos(i) = traj_state.response.position[i];
00312       jnt_pos(i) = 0;
00313     }
00314 
00315     int count = 0;
00316     int limit_flips = 0;
00317     float correction_angle = 2*M_PI;
00318     float correction_delta = 2*M_PI;
00319     while( ros::ok() && fabs(correction_delta) > 0.001)
00320     {
00321       //get the pose and jacobian for the current joint positions
00322       KDL::Frame pose;
00323       pose_solver_->JntToCart(jnt_pos, pose);
00324       jac_solver_->JntToJac(jnt_pos, jacobian);
00325 
00326       tf::Transform frame_in_root;
00327       tf::poseKDLToTF(pose, frame_in_root);
00328 
00329       tf::Vector3 axis_in_frame = pointing_axis_.normalized();
00330       tf::Vector3 target_from_frame = (target_in_root_ - frame_in_root.getOrigin()).normalized();
00331       tf::Vector3 current_in_frame = frame_in_root.getBasis().inverse()*target_from_frame;
00332       float prev_correction = correction_angle;
00333       correction_angle = current_in_frame.angle(axis_in_frame);
00334       correction_delta = correction_angle - prev_correction;
00335       ROS_DEBUG("At step %d, joint poses are %.4f and %.4f, angle error is %f", count, jnt_pos(0), jnt_pos(1), correction_angle);
00336       if(correction_angle < 0.5*success_angle_threshold_) break;
00337       tf::Vector3 correction_axis = frame_in_root.getBasis()*(axis_in_frame.cross(current_in_frame).normalized());
00338       //printVector3("correction_axis in root:", correction_axis);
00339       tf::Transform correction_tf(tf::Quaternion(correction_axis, 0.5*correction_angle), tf::Vector3(0,0,0));
00340       KDL::Frame correction_kdl;
00341       tf::transformTFToKDL(correction_tf, correction_kdl);
00342 
00343       // We apply a "wrench" proportional to the desired correction
00344       KDL::Frame identity_kdl;
00345       KDL::Twist twist = diff(correction_kdl, identity_kdl);
00346       KDL::Wrench wrench_desi;
00347       for (unsigned int i=0; i<6; i++)
00348         wrench_desi(i) = -1.0*twist(i);
00349 
00350       // Converts the "wrench" into "joint corrections" with a jacbobian-transpose
00351       for (unsigned int i = 0; i < joints; i++)
00352       {
00353         jnt_eff(i) = 0;
00354         for (unsigned int j=0; j<6; j++)
00355           jnt_eff(i) += (jacobian(j,i) * wrench_desi(j));
00356         jnt_pos(i) += jnt_eff(i);
00357       }
00358 
00359       // account for pan_link joint limit in back.
00360       if(jnt_pos(0) < limits_[0].lower && limit_flips++ == 0){ jnt_pos(0) += 1.5*M_PI; }
00361       if(jnt_pos(0) > limits_[0].upper && limit_flips++ == 0){ jnt_pos(0) -= 1.5*M_PI; }
00362 
00363       jnt_pos(1) = std::max(limits_[1].lower, jnt_pos(1));
00364       jnt_pos(1) = std::min(limits_[1].upper, jnt_pos(1));
00365 
00366       count++;
00367 
00368       if(limit_flips > 1){
00369         ROS_ERROR("Goal is out of joint limits, trying to point there anyway... \n");
00370         break;
00371       }
00372     }
00373     ROS_DEBUG("Iterative solver took %d steps", count);
00374     
00375     std::vector<double> q_goal(joints);
00376 
00377     for(unsigned int i = 0; i < joints; i++)
00378     {
00379       jnt_pos(i) = std::max(limits_[i].lower, jnt_pos(i));
00380       jnt_pos(i) = std::min(limits_[i].upper, jnt_pos(i));
00381       q_goal[i] = jnt_pos(i);
00382       ROS_DEBUG("Joint %d %s: %f", i, joint_names_[i].c_str(), jnt_pos(i));
00383     }
00384 
00385     if (has_active_goal_)
00386     {
00387       active_goal_.setCanceled();
00388       has_active_goal_ = false;
00389     }
00390 
00391     gh.setAccepted();
00392     active_goal_ = gh;
00393     has_active_goal_ = true;
00394 
00395 
00396     // Computes the duration of the movement.
00397     ros::Duration min_duration(0.01);
00398 
00399     if (gh.getGoal()->min_duration > min_duration)
00400         min_duration = gh.getGoal()->min_duration;
00401 
00402     // Determines if we need to increase the duration of the movement in order to enforce a maximum velocity.
00403     if (gh.getGoal()->max_velocity > 0)
00404     {
00405       // Very approximate velocity limiting.
00406       double dist = sqrt(pow(q_goal[0] - traj_state.response.position[0], 2) +
00407                          pow(q_goal[1] - traj_state.response.position[1], 2));
00408       ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity);
00409       if (limit_from_velocity > min_duration)
00410         min_duration = limit_from_velocity;
00411     }
00412 
00413 
00414     // Computes the command to send to the trajectory controller.
00415     trajectory_msgs::JointTrajectory traj;
00416     traj.header.stamp = traj_state.request.time;
00417 
00418     traj.joint_names.push_back(traj_state.response.name[0]);
00419     traj.joint_names.push_back(traj_state.response.name[1]);
00420 
00421     traj.points.resize(2);
00422     traj.points[0].positions = traj_state.response.position;
00423     traj.points[0].velocities = traj_state.response.velocity;
00424     traj.points[0].time_from_start = ros::Duration(0.0);
00425     traj.points[1].positions = q_goal;
00426     traj.points[1].velocities.push_back(0);
00427     traj.points[1].velocities.push_back(0);
00428     traj.points[1].time_from_start = ros::Duration(min_duration);
00429 
00430     pub_controller_command_.publish(traj);
00431   }
00432 
00433   
00434   void watchdog(const ros::TimerEvent &e)
00435   {
00436     ros::Time now = ros::Time::now();
00437 
00438     // Aborts the active goal if the controller does not appear to be active.
00439     if (has_active_goal_)
00440     {
00441       bool should_abort = false;
00442       if (!last_controller_state_)
00443       {
00444         should_abort = true;
00445         ROS_WARN("Aborting goal because we have never heard a controller state message.");
00446       }
00447       else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
00448       {
00449         should_abort = true;
00450         ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
00451                  (now - last_controller_state_->header.stamp).toSec());
00452       }
00453 
00454       if (should_abort)
00455       {
00456         // Stops the controller.
00457         trajectory_msgs::JointTrajectory empty;
00458         empty.joint_names = joint_names_;
00459         pub_controller_command_.publish(empty);
00460 
00461         // Marks the current goal as aborted.
00462         active_goal_.setAborted();
00463         has_active_goal_ = false;
00464       }
00465     }
00466   }
00467 
00468 
00469   void cancelCB(GoalHandle gh)
00470   {
00471     if (active_goal_ == gh)
00472     {
00473       // Stops the controller.
00474       trajectory_msgs::JointTrajectory empty;
00475       empty.joint_names = joint_names_;
00476       pub_controller_command_.publish(empty);
00477 
00478       // Marks the current goal as canceled.
00479       active_goal_.setCanceled();
00480       has_active_goal_ = false;
00481     }
00482   }
00483 
00484   pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_;
00485   void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
00486   {
00487     last_controller_state_ = msg;
00488     ros::Time now = ros::Time::now();
00489 
00490     if (!has_active_goal_)
00491       return;
00492 
00494     try
00495     {
00496       KDL::JntArray jnt_pos(msg->joint_names.size());
00497       for(unsigned int i = 0; i < msg->joint_names.size(); i++)
00498         jnt_pos(i) = msg->actual.positions[i];
00499 
00500       KDL::Frame pose;
00501       pose_solver_->JntToCart(jnt_pos, pose);
00502 
00503       tf::Transform frame_in_root;
00504       tf::poseKDLToTF(pose, frame_in_root);
00505 
00506       tf::Vector3 axis_in_frame = pointing_axis_.normalized();
00507       tf::Vector3 target_from_frame = target_in_root_ - frame_in_root.getOrigin();
00508 
00509       target_from_frame.normalize();
00510       tf::Vector3 current_in_frame = frame_in_root.getBasis().inverse()*target_from_frame;
00511 
00512       pr2_controllers_msgs::PointHeadFeedback feedback;
00513       feedback.pointing_angle_error = current_in_frame.angle(axis_in_frame);
00514       active_goal_.publishFeedback(feedback);
00515 
00516       if (feedback.pointing_angle_error < success_angle_threshold_)
00517       {
00518         active_goal_.setSucceeded();
00519         has_active_goal_ = false;
00520       }
00521     }
00522     catch(const tf::TransformException &ex)
00523     {
00524       ROS_ERROR("Could not transform: %s", ex.what());
00525     }
00526   }
00527 
00528 
00529 };
00530 
00531 int main(int argc, char** argv)
00532 {
00533   ros::init(argc, argv, "point_head_action");
00534   ros::NodeHandle node;
00535   ControlHead ch(node);
00536   ros::spin();
00537   return 0;
00538 }
00539 


pr2_head_action
Author(s): Stuart Glaser
autogenerated on Sat Jun 8 2019 20:49:22