cartesian_trajectory_controller.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*
00031  * Author: Wim Meeussen
00032  */
00033 
00034 #include <algorithm>
00035 #include "kdl/chainfksolverpos_recursive.hpp"
00036 #include "simple_Jtranspose_controller/CheckMoving.h"
00037 #include "simple_Jtranspose_controller/cartesian_trajectory_controller.h"
00038 #include "pluginlib/class_list_macros.h"
00039 
00040 
00041 using namespace KDL;
00042 using namespace tf;
00043 using namespace ros;
00044 
00045 using namespace controller;
00046 
00047 PLUGINLIB_REGISTER_CLASS(CartesianTrajectoryController, controller::CartesianTrajectoryController, pr2_controller_interface::Controller)
00048 
00049 namespace controller {
00050 
00051 
00052 CartesianTrajectoryController::CartesianTrajectoryController()
00053 : jnt_to_pose_solver_(NULL),
00054   motion_profile_(6, VelocityProfile_Trap(0,0))
00055 {}
00056 
00057 CartesianTrajectoryController::~CartesianTrajectoryController()
00058 {}
00059 
00060 
00061 bool CartesianTrajectoryController::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle& n)
00062 {
00063   node_ = n;
00064 
00065   // get name of root and tip from the parameter server
00066   std::string tip_name;
00067   if (!node_.getParam("root_name", root_name_)){
00068     ROS_ERROR("CartesianTrajectoryController: No root name found on parameter server");
00069     return false;
00070   }
00071   if (!node_.getParam("tip_name", tip_name)){
00072     ROS_ERROR("CartesianTrajectoryController: No tip name found on parameter server");
00073     return false;
00074   }
00075 
00076   // test if we got robot pointer
00077   assert(robot_state);
00078   robot_state_ = robot_state;
00079 
00080   // create robot chain from root to tip
00081   if (!chain_.init(robot_state, root_name_, tip_name))
00082     return false;
00083   chain_.toKDL(kdl_chain_);
00084 
00085   // create solver
00086   jnt_to_pose_solver_.reset(new ChainFkSolverPos_recursive(kdl_chain_));
00087   jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00088 
00089   // initialize motion profile
00090   double max_vel_trans, max_vel_rot, max_acc_trans, max_acc_rot;
00091   node_.param("max_vel_trans", max_vel_trans, 0.0) ;
00092   node_.param("max_vel_rot", max_vel_rot, 0.0) ;
00093   node_.param("max_acc_trans", max_acc_trans, 0.0) ;
00094   node_.param("max_acc_rot", max_acc_rot, 0.0) ;
00095   for (unsigned int i=0; i<3; i++){
00096     motion_profile_[i  ].SetMax(max_vel_trans, max_acc_trans);
00097     motion_profile_[i+3].SetMax(max_vel_rot,   max_acc_rot);
00098   }
00099 
00100   // get a pointer to the pose controller
00101   std::string output;
00102   if (!node_.getParam("output", output)){
00103     ROS_ERROR("CartesianTrajectoryController: No ouptut name found on parameter server");
00104     return false;
00105   }
00106   if (!getController<CartesianPoseController>(output, AFTER_ME, pose_controller_)){
00107     ROS_ERROR("CartesianTrajectoryController: could not connect to pose controller");
00108     return false;
00109   }
00110 
00111   // subscribe to pose commands
00112   /*
00113   command_notifier_.reset(new MessageFilter<geometry_msgs::PoseStamped>(tf_,
00114                                                                        boost::bind(&CartesianTrajectoryController::command, this, _1),
00115                                                                        node_.getNamespace() + "/command", root_name_, 1));
00116   */
00117   //command_sub_ = node_.subscribe(node_.getNamespace() + "/command", 1, &CartesianTrajectoryController::command, this);
00118   
00119 
00120   // advertise services
00121   move_to_srv_ = node_.advertiseService("move_to", &CartesianTrajectoryController::moveTo, this);
00122   preempt_srv_ = node_.advertiseService("preempt", &CartesianTrajectoryController::preempt, this);
00123   check_moving_srv_ = node_.advertiseService("check_moving", &CartesianTrajectoryController::checkMoving, this);
00124 
00125   return true;
00126 }
00127 
00128 
00129 
00130 
00131 //service callback to return is_moving_
00132 bool CartesianTrajectoryController::checkMoving(simple_Jtranspose_controller::CheckMoving::Request &req, simple_Jtranspose_controller::CheckMoving::Response &res)
00133 {
00134   res.ismoving = is_moving_;
00135   return true;
00136 }
00137 
00138 
00139 
00140 
00141 bool CartesianTrajectoryController::moveTo(const geometry_msgs::PoseStamped& pose, const geometry_msgs::Twist& tolerance, double duration)
00142 {
00143   //ROS_INFO("Cartesian trajectory controller moving to new pose");
00144 
00145   // don't do anything when still moving
00146   if (is_moving_){
00147     ROS_WARN("Controller is still moving!  Rejecting new pose");
00148     return false;
00149   }
00150 
00151   //normalize pose orientation
00152   geometry_msgs::PoseStamped pose_normalized;
00153   pose_normalized.header = pose.header;
00154   pose_normalized.pose.position = pose.pose.position;
00155   double x = pose.pose.orientation.x;
00156   double y = pose.pose.orientation.y;
00157   double z = pose.pose.orientation.z;
00158   double w = pose.pose.orientation.w;
00159   double mag = sqrt(x*x+y*y+z*z+w*w);
00160   pose_normalized.pose.orientation.x = x/mag;
00161   pose_normalized.pose.orientation.y = y/mag;
00162   pose_normalized.pose.orientation.z = z/mag;
00163   pose_normalized.pose.orientation.w = w/mag;
00164   //ROS_ERROR("normalized pose: %2.3f %2.3f %2.3f %2.3f", pose_normalized.pose.orientation.x, pose_normalized.pose.orientation.y, pose_normalized.pose.orientation.z, pose_normalized.pose.orientation.w);
00165 
00166   // convert message to transform
00167   Stamped<Pose> pose_stamped;
00168   poseStampedMsgToTF(pose_normalized, pose_stamped);
00169 
00170   // convert to reference frame of root link of the controller chain
00171   Duration timeout = Duration().fromSec(2.0);
00172   std::string error_msg;
00173   if (!tf_.waitForTransform(root_name_, pose.header.frame_id, pose_stamped.stamp_, timeout, Duration(0.01), &error_msg)){
00174     ROS_ERROR("CartesianTrajectoryController: %s", error_msg.c_str());
00175     return false;
00176   }
00177   tf_.transformPose(root_name_, pose_stamped, pose_stamped);
00178 
00179   // trajectory from pose_begin to pose_end
00180   TransformToFrame(pose_stamped, pose_end_);
00181   pose_begin_ = pose_current_;
00182 
00183   //btMatrix3x3 bt_mat = pose_stamped.getBasis();
00184   //ROS_ERROR("pose_stamped:\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n", bt_mat[0][0],bt_mat[0][1],bt_mat[0][2],bt_mat[1][0],bt_mat[1][1],bt_mat[1][2],bt_mat[2][0],bt_mat[2][1],bt_mat[2][2]);
00185 
00186   //KDL::Rotation mat = pose_end_.M;
00187   //ROS_ERROR("pose_end:\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n", mat(0,0),mat(0,1),mat(0,2),mat(1,0),mat(1,1),mat(1,2),mat(2,0),mat(2,1),mat(2,2));
00188 
00189 
00190   max_duration_ = 0;
00191   Twist twist_move = diff(pose_begin_, pose_end_);
00192 
00193   // Set motion profiles
00194   for (unsigned int i=0; i<6; i++){
00195     motion_profile_[i].SetProfileDuration( 0, twist_move(i), duration);
00196     max_duration_ = max( max_duration_, motion_profile_[i].Duration() );
00197   }
00198 
00199   // Rescale trajectories to maximal duration
00200   for (unsigned int i=0; i<6; i++)
00201     motion_profile_[i].SetProfileDuration( 0, twist_move(i), max_duration_ );
00202 
00203   // set tolerance
00204   tolerance_.vel(0) = tolerance.linear.x;
00205   tolerance_.vel(1) = tolerance.linear.y;
00206   tolerance_.vel(2) = tolerance.linear.z;
00207   tolerance_.rot(0) = tolerance.angular.x;
00208   tolerance_.rot(1) = tolerance.angular.y;
00209   tolerance_.rot(2) = tolerance.angular.z;
00210 
00211   time_passed_ = 0;
00212 
00213   exceed_tolerance_ = false;
00214   request_preempt_ = false;
00215   is_moving_ = true;
00216 
00217   ROS_INFO("CartesianTrajectoryController: %s will move to new pose in %f seconds", controller_name_.c_str(), max_duration_);
00218 
00219   return true;
00220 }
00221 
00222 
00223 
00224 void CartesianTrajectoryController::starting()
00225 {
00226   // time
00227   last_time_ = robot_state_->getTime();
00228 
00229   // set desired pose to current pose
00230   pose_current_ = getPose();
00231   twist_current_ = Twist::Zero();
00232 
00233   // start not moving
00234   is_moving_ = false;
00235   request_preempt_ = false;
00236 }
00237 
00238 
00239 
00240 
00241 void CartesianTrajectoryController::update()
00242 {
00243   // get time
00244   ros::Time time = robot_state_->getTime();
00245   ros::Duration dt = time - last_time_;
00246   last_time_ = time;
00247 
00248   // preempt trajectory
00249   if (request_preempt_){
00250     twist_current_ = Twist::Zero();
00251     is_moving_ = false;
00252   }
00253 
00254   // if we are moving
00255   if (is_moving_){
00256     time_passed_ += dt.toSec();
00257 
00258     // check tolerance
00259     for (unsigned int i=0; i<6; i++){
00260       if (tolerance_[i] != 0 && pose_controller_->twist_error_[i] > tolerance_[i]){
00261         exceed_tolerance_ = true;
00262         is_moving_ = false;
00263         ROS_INFO("Cartesian trajectory exceeded tolerance");
00264       }
00265     }
00266 
00267     // ended trajectory
00268     if (time_passed_ > max_duration_){
00269       twist_current_ = Twist::Zero();
00270       pose_current_  = pose_end_;
00271       is_moving_ = false;
00272       KDL::Rotation mat = pose_current_.M;
00273       //ROS_ERROR("pose_current:\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n %0.2f %0.2f %0.2f\n", mat(0,0),mat(0,1),mat(0,2),mat(1,0),mat(1,1),mat(1,2),mat(2,0),mat(2,1),mat(2,2));
00274 
00275 
00276     }
00277     // still in trajectory
00278     else{
00279       // pose
00280       Twist twist_begin_current = Twist(Vector(motion_profile_[0].Pos(time_passed_),
00281                                                motion_profile_[1].Pos(time_passed_),
00282                                                motion_profile_[2].Pos(time_passed_)),
00283                                         Vector(motion_profile_[3].Pos(time_passed_),
00284                                                motion_profile_[4].Pos(time_passed_),
00285                                                motion_profile_[5].Pos(time_passed_)) );
00286       pose_current_ = Frame( pose_begin_.M * Rot( pose_begin_.M.Inverse( twist_begin_current.rot ) ),
00287                              pose_begin_.p + twist_begin_current.vel);
00288 
00289       // twist
00290       for(unsigned int i=0; i<6; i++)
00291         twist_current_(i) = motion_profile_[i].Vel( time_passed_ );
00292     }
00293   }
00294 
00295   // send output to pose controller
00296   pose_controller_->pose_desi_ = pose_current_;
00297   pose_controller_->twist_ff_ = twist_current_;
00298 }
00299 
00300 
00301 
00302 Frame CartesianTrajectoryController::getPose()
00303 {
00304   // get the joint positions and velocities
00305   chain_.getPositions(jnt_pos_);
00306 
00307   // get cartesian pose
00308   Frame result;
00309   jnt_to_pose_solver_->JntToCart(jnt_pos_, result);
00310 
00311   return result;
00312 }
00313 
00314 
00315 bool CartesianTrajectoryController::moveTo(simple_Jtranspose_controller::MoveToPose::Request &req,
00316                                            simple_Jtranspose_controller::MoveToPose::Response &resp)
00317 {
00318   ROS_DEBUG("in cartesian traj move_to service");
00319 
00320   if (!moveTo(req.pose, req.tolerance, 0.0)){
00321     ROS_ERROR("CartesianTrajectoryController: not starting trajectory because either previous one is still running or the transform frame could not be found");
00322     return false;
00323   }
00324   /*
00325   ros::Duration timeout = Duration().fromSec(3.0);
00326   ros::Duration traj_duration = Duration().fromSec(max_duration_);
00327   ros::Time start_time = ros::Time::now();
00328 
00329 
00330 
00331   while (is_moving_){
00332     Duration().fromSec(0.1).sleep();
00333     if (ros::Time::now() > start_time + timeout + traj_duration){
00334       ROS_ERROR("CartesianTrajectoryController: timeout");
00335       return false;
00336     }
00337   }
00338 
00339   if (request_preempt_){
00340     ROS_ERROR("CartesianTrajectoryController: trajectory preempted");
00341     return false;
00342   }
00343   else if (exceed_tolerance_){
00344     ROS_ERROR("CartesianTrajectoryController: exceeded trajectory tolerance");
00345     return false;
00346   }
00347   else{
00348     ROS_DEBUG("CartesianTrajectoryController: moveto finished successfully");
00349     return true;
00350     }*/
00351   return true;
00352 }
00353 
00354 
00355 /*
00356 void CartesianTrajectoryController::command(const MessageFilter<geometry_msgs::PoseStamped>::MessagePtr& pose_msg)
00357 {
00358   moveTo(*pose_msg);
00359   }*/
00360 
00361 
00362 bool CartesianTrajectoryController::preempt(std_srvs::Empty::Request &req,
00363                                             std_srvs::Empty::Response &resp)
00364 {
00365   // you can only preempt is the robot is moving
00366   if (!is_moving_)
00367     return false;
00368 
00369   request_preempt_ = true;
00370 
00371   // wait for robot to stop moving
00372   Duration sleep_time = Duration().fromSec(0.01);
00373   while (is_moving_)
00374     sleep_time.sleep();
00375 
00376   return true;
00377 }
00378 
00379 
00380 
00381 void CartesianTrajectoryController::TransformToFrame(const Transform& trans, Frame& frame)
00382 {
00383   frame.p(0) = trans.getOrigin().x();
00384   frame.p(1) = trans.getOrigin().y();
00385   frame.p(2) = trans.getOrigin().z();
00386 
00387   int i, j;
00388   btMatrix3x3 bt_mat = trans.getBasis();
00389   for(i=0; i<3; i++){
00390     for(j=0; j<3; j++){
00391       frame.M(i,j) = bt_mat[i][j];
00392     }
00393   }
00394 }
00395 
00396 
00397 
00398 }; // namespace
00399 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


simple_Jtranspose_controller
Author(s): Kaijen Hsiao
autogenerated on Tue Oct 30 2012 07:57:23