00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
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
00077 assert(robot_state);
00078 robot_state_ = robot_state;
00079
00080
00081 if (!chain_.init(robot_state, root_name_, tip_name))
00082 return false;
00083 chain_.toKDL(kdl_chain_);
00084
00085
00086 jnt_to_pose_solver_.reset(new ChainFkSolverPos_recursive(kdl_chain_));
00087 jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00088
00089
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
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
00112
00113
00114
00115
00116
00117
00118
00119
00120
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
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
00144
00145
00146 if (is_moving_){
00147 ROS_WARN("Controller is still moving! Rejecting new pose");
00148 return false;
00149 }
00150
00151
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
00165
00166
00167 Stamped<Pose> pose_stamped;
00168 poseStampedMsgToTF(pose_normalized, pose_stamped);
00169
00170
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
00180 TransformToFrame(pose_stamped, pose_end_);
00181 pose_begin_ = pose_current_;
00182
00183
00184
00185
00186
00187
00188
00189
00190 max_duration_ = 0;
00191 Twist twist_move = diff(pose_begin_, pose_end_);
00192
00193
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
00200 for (unsigned int i=0; i<6; i++)
00201 motion_profile_[i].SetProfileDuration( 0, twist_move(i), max_duration_ );
00202
00203
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
00227 last_time_ = robot_state_->getTime();
00228
00229
00230 pose_current_ = getPose();
00231 twist_current_ = Twist::Zero();
00232
00233
00234 is_moving_ = false;
00235 request_preempt_ = false;
00236 }
00237
00238
00239
00240
00241 void CartesianTrajectoryController::update()
00242 {
00243
00244 ros::Time time = robot_state_->getTime();
00245 ros::Duration dt = time - last_time_;
00246 last_time_ = time;
00247
00248
00249 if (request_preempt_){
00250 twist_current_ = Twist::Zero();
00251 is_moving_ = false;
00252 }
00253
00254
00255 if (is_moving_){
00256 time_passed_ += dt.toSec();
00257
00258
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
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
00274
00275
00276 }
00277
00278 else{
00279
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
00290 for(unsigned int i=0; i<6; i++)
00291 twist_current_(i) = motion_profile_[i].Vel( time_passed_ );
00292 }
00293 }
00294
00295
00296 pose_controller_->pose_desi_ = pose_current_;
00297 pose_controller_->twist_ff_ = twist_current_;
00298 }
00299
00300
00301
00302 Frame CartesianTrajectoryController::getPose()
00303 {
00304
00305 chain_.getPositions(jnt_pos_);
00306
00307
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
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351 return true;
00352 }
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362 bool CartesianTrajectoryController::preempt(std_srvs::Empty::Request &req,
00363 std_srvs::Empty::Response &resp)
00364 {
00365
00366 if (!is_moving_)
00367 return false;
00368
00369 request_preempt_ = true;
00370
00371
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 };
00399