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
00035 #include <boost/thread.hpp>
00036 #include <boost/shared_ptr.hpp>
00037 #include <boost/scoped_ptr.hpp>
00038
00039 #include <Eigen/Core>
00040 #include <Eigen/Geometry>
00041 #include <Eigen/LU>
00042
00043 #include <kdl/chainfksolver.hpp>
00044 #include <kdl/chainfksolverpos_recursive.hpp>
00045 #include <kdl/chain.hpp>
00046 #include <kdl/chainjnttojacsolver.hpp>
00047 #include <kdl/frames.hpp>
00048
00049 #include <ros/ros.h>
00050
00051 #include <geometry_msgs/PoseStamped.h>
00052 #include <geometry_msgs/TwistStamped.h>
00053 #include <teleop_controllers/JTTaskControllerState.h>
00054 #include <teleop_controllers/CartesianGains.h>
00055
00056 #include <pluginlib/class_list_macros.h>
00057 #include <angles/angles.h>
00058 #include <control_toolbox/pid.h>
00059 #include <eigen_conversions/eigen_kdl.h>
00060 #include <eigen_conversions/eigen_msg.h>
00061 #include <pr2_controller_interface/controller.h>
00062 #include <pr2_mechanism_model/chain.h>
00063 #include <realtime_tools/realtime_publisher.h>
00064 #include <tf/transform_listener.h>
00065
00066 #include <rosrt/rosrt.h>
00067
00068 namespace pr2_teleop {
00069
00070 template <int Joints>
00071 struct Kin
00072 {
00073 typedef Eigen::Matrix<double, Joints, 1> JointVec;
00074 typedef Eigen::Matrix<double, 6, Joints> Jacobian;
00075
00076 Kin(const KDL::Chain &kdl_chain) :
00077 fk_solver_(kdl_chain), jac_solver_(kdl_chain),
00078 kdl_q(Joints), kdl_J(Joints)
00079 {
00080 }
00081 ~Kin()
00082 {
00083 }
00084
00085 void fk(const JointVec &q, Eigen::Affine3d &x)
00086 {
00087 kdl_q.data = q;
00088 KDL::Frame kdl_x;
00089 fk_solver_.JntToCart(kdl_q, kdl_x);
00090 tf::transformKDLToEigen(kdl_x, x);
00091 }
00092 void jac(const JointVec &q, Jacobian &J)
00093 {
00094 kdl_q.data = q;
00095 jac_solver_.JntToJac(kdl_q, kdl_J);
00096 J = kdl_J.data;
00097 }
00098
00099 KDL::ChainFkSolverPos_recursive fk_solver_;
00100 KDL::ChainJntToJacSolver jac_solver_;
00101 KDL::JntArray kdl_q;
00102 KDL::Jacobian kdl_J;
00103 };
00104
00105 class JTTaskController : public pr2_controller_interface::Controller
00106 {
00107 public:
00108
00109
00110 EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
00111 private:
00112 enum { Joints = 7 };
00113 typedef Eigen::Matrix<double, Joints, 1> JointVec;
00114 typedef Eigen::Matrix<double, 6, 1> CartVec;
00115 typedef Eigen::Matrix<double, 6, Joints> Jacobian;
00116 typedef teleop_controllers::JTTaskControllerState StateMsg;
00117 public:
00118 JTTaskController();
00119 ~JTTaskController();
00120
00121 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00122 void starting();
00123 void update();
00124
00125 Eigen::Affine3d x_desi_, x_desi_filtered_;
00126 CartVec wrench_desi_;
00127
00128 ros::NodeHandle node_;
00129 ros::Subscriber sub_gains_;
00130 ros::Subscriber sub_posture_;
00131 ros::Subscriber sub_pose_;
00132 tf::TransformListener tf_;
00133
00134 rosrt::Publisher<StateMsg> pub_state_;
00135 rosrt::Publisher<geometry_msgs::PoseStamped> pub_x_, pub_x_desi_;
00136 rosrt::Publisher<geometry_msgs::Twist> pub_xd_, pub_xd_desi_;
00137 rosrt::Publisher<geometry_msgs::Twist> pub_x_err_, pub_wrench_;
00138 rosrt::Publisher<std_msgs::Float64MultiArray> pub_tau_;
00139
00140 std::string root_name_, tip_name_;
00141 ros::Time last_time_;
00142 int loop_count_;
00143 pr2_mechanism_model::RobotState *robot_state_;
00144
00145 pr2_mechanism_model::Chain chain_;
00146 boost::scoped_ptr<Kin<Joints> > kin_;
00147 Eigen::Matrix<double,6,1> Kp, Kd;
00148 Eigen::Matrix<double,6,6> St;
00149 bool use_tip_frame_;
00150 double pose_command_filter_;
00151 double vel_saturation_trans_, vel_saturation_rot_;
00152 JointVec saturation_;
00153 JointVec joint_dd_ff_;
00154 double joint_vel_filter_;
00155 double jacobian_inverse_damping_;
00156 JointVec q_posture_;
00157 double k_posture_;
00158 bool use_posture_;
00159
00160
00161 double res_force_, res_position_;
00162 double res_torque_, res_orientation_;
00163
00164 Eigen::Affine3d last_pose_;
00165 CartVec last_wrench_;
00166 double last_stiffness_, last_compliance_;
00167 double last_Dx_, last_Df_;
00168
00169
00170 JointVec qdot_filtered_;
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185 void setGains(const teleop_controllers::CartesianGains::ConstPtr &msg)
00186 {
00187
00188
00189
00190
00191
00192 if (msg->gains.size() >= 6)
00193 for (size_t i = 0; i < 6; ++i)
00194 Kp[i] = msg->gains[i];
00195 if (msg->gains.size() == 12)
00196 for (size_t i = 0; i < 6; ++i)
00197 Kd[i] = msg->gains[6+i];
00198
00199
00200 if(!msg->header.frame_id.compare(root_name_))
00201 {
00202 use_tip_frame_ = false;
00203 ROS_INFO("New gains in root frame [%s]: %.1lf, %.1lf, %.1lf %.1lf, %.1lf, %.1lf",
00204 root_name_.c_str(), Kp[0], Kp[1], Kp[2], Kp[3], Kp[4], Kp[5]);
00205 St.setIdentity();
00206 }
00207 else if(!msg->header.frame_id.compare(tip_name_))
00208 {
00209 use_tip_frame_ = true;
00210 ROS_INFO("New gains in tip frame [%s]: %.1lf, %.1lf, %.1lf %.1lf, %.1lf, %.1lf",
00211 tip_name_.c_str(), Kp[0], Kp[1], Kp[2], Kp[3], Kp[4], Kp[5]);
00212
00213 }
00214 else
00215 {
00216 use_tip_frame_ = false;
00217
00218 geometry_msgs::PoseStamped in_root;
00219 in_root.pose.orientation.w = 1.0;
00220 in_root.header.frame_id = msg->header.frame_id;
00221
00222 try {
00223 tf_.waitForTransform(root_name_, msg->header.frame_id, msg->header.stamp, ros::Duration(0.1));
00224 tf_.transformPose(root_name_, in_root, in_root);
00225 }
00226 catch (const tf::TransformException &ex)
00227 {
00228 ROS_ERROR("Failed to transform: %s", ex.what());
00229 return;
00230 }
00231
00232 Eigen::Affine3d t;
00233
00234 tf::poseMsgToEigen(in_root.pose, t);
00235
00236 St <<
00237 t(0,0),t(0,1),t(0,2),0,0,0,
00238 t(1,0),t(1,1),t(1,2),0,0,0,
00239 t(2,0),t(2,1),t(2,2),0,0,0,
00240 0,0,0,t(0,0),t(0,1),t(0,2),
00241 0,0,0,t(1,0),t(1,1),t(1,2),
00242 0,0,0,t(2,0),t(2,1),t(2,2);
00243
00244 St.transposeInPlace();
00245
00246 ROS_INFO("New gains in arbitrary frame [%s]: %.1lf, %.1lf, %.1lf %.1lf, %.1lf, %.1lf",
00247 msg->header.frame_id.c_str(), Kp[0], Kp[1], Kp[2], Kp[3], Kp[4], Kp[5]);
00248 }
00249 }
00250
00251 void commandPosture(const std_msgs::Float64MultiArray::ConstPtr &msg)
00252 {
00253 if (msg->data.size() == 0) {
00254 use_posture_ = false;
00255 ROS_INFO("Posture turned off");
00256 }
00257 else if ((int)msg->data.size() != q_posture_.size()) {
00258 ROS_ERROR("Posture message had the wrong size: %d", (int)msg->data.size());
00259 return;
00260 }
00261 else
00262 {
00263 use_posture_ = true;
00264 for (int j = 0; j < Joints; ++j)
00265 q_posture_[j] = msg->data[j];
00266 }
00267 }
00268
00269 void commandPose(const geometry_msgs::PoseStamped::ConstPtr &command)
00270 {
00271 geometry_msgs::PoseStamped in_root;
00272 try {
00273 tf_.waitForTransform(root_name_, command->header.frame_id, command->header.stamp, ros::Duration(0.1));
00274 tf_.transformPose(root_name_, *command, in_root);
00275 }
00276 catch (const tf::TransformException &ex)
00277 {
00278 ROS_ERROR("Failed to transform: %s", ex.what());
00279 return;
00280 }
00281
00282 tf::poseMsgToEigen(in_root.pose, x_desi_);
00283 }
00284 };
00285
00286
00287 JTTaskController::JTTaskController()
00288 : robot_state_(NULL), use_posture_(false)
00289 {}
00290
00291 JTTaskController::~JTTaskController()
00292 {
00293 sub_gains_.shutdown();
00294 sub_posture_.shutdown();
00295 sub_pose_.shutdown();
00296 }
00297
00298
00299 bool JTTaskController::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &n)
00300 {
00301 rosrt::init();
00302 node_ = n;
00303
00304 ROS_INFO_STREAM("JTTask controller compiled at " << __TIME__ );
00305
00306
00307 if (!node_.getParam("root_name", root_name_)){
00308 ROS_ERROR("JTTaskController: No root name found on parameter server (namespace: %s)",
00309 node_.getNamespace().c_str());
00310 return false;
00311 }
00312 if (!node_.getParam("tip_name", tip_name_)){
00313 ROS_ERROR("JTTaskController: No tip name found on parameter server (namespace: %s)",
00314 node_.getNamespace().c_str());
00315 return false;
00316 }
00317
00318
00319 assert(robot_state);
00320 robot_state_ = robot_state;
00321
00322
00323 if (!chain_.init(robot_state_, root_name_, tip_name_))
00324 return false;
00325 if (!chain_.allCalibrated())
00326 {
00327 ROS_ERROR("Not all joints in the chain are calibrated (namespace: %s)", node_.getNamespace().c_str());
00328 return false;
00329 }
00330
00331
00332
00333 KDL::Chain kdl_chain;
00334 chain_.toKDL(kdl_chain);
00335 kin_.reset(new Kin<Joints>(kdl_chain));
00336
00337
00338 double kp_trans, kd_trans, kp_rot, kd_rot;
00339 if (!node_.getParam("cart_gains/trans/p", kp_trans) ||
00340 !node_.getParam("cart_gains/trans/d", kd_trans))
00341 {
00342 ROS_ERROR("P and D translational gains not specified (namespace: %s)", node_.getNamespace().c_str());
00343 return false;
00344 }
00345 if (!node_.getParam("cart_gains/rot/p", kp_rot) ||
00346 !node_.getParam("cart_gains/rot/d", kd_rot))
00347 {
00348 ROS_ERROR("P and D rotational gains not specified (namespace: %s)", node_.getNamespace().c_str());
00349 return false;
00350 }
00351 Kp << kp_trans, kp_trans, kp_trans, kp_rot, kp_rot, kp_rot;
00352 Kd << kd_trans, kd_trans, kd_trans, kd_rot, kd_rot, kd_rot;
00353
00354
00355 use_tip_frame_ = false;
00356 if (!node_.getParam("use_tip_frame", use_tip_frame_)){
00357 ROS_WARN("JTTaskController: use_tip_frame was not specified, assuming 'false': %s)",
00358 node_.getNamespace().c_str());
00359 }
00360 St.setIdentity();
00361
00362 node_.param("pose_command_filter", pose_command_filter_, 1.0);
00363
00364
00365 node_.param("vel_saturation_trans", vel_saturation_trans_, 0.0);
00366 node_.param("vel_saturation_rot", vel_saturation_rot_, 0.0);
00367
00368 node_.param("jacobian_inverse_damping", jacobian_inverse_damping_, 0.0);
00369 node_.param("joint_vel_filter", joint_vel_filter_, 1.0);
00370
00371
00372 for (int i = 0; i < Joints; ++i)
00373 node_.param("joint_feedforward/" + chain_.getJoint(i)->joint_->name, joint_dd_ff_[i], 0.0);
00374 for (int i = 0; i < Joints; ++i)
00375 node_.param("saturation/" + chain_.getJoint(i)->joint_->name, saturation_[i], 0.0);
00376
00377
00378 node_.param("k_posture", k_posture_, 1.0);
00379
00380 node_.param("resolution/force", res_force_, 0.01);
00381 node_.param("resolution/position", res_position_, 0.001);
00382 node_.param("resolution/torque", res_torque_, 0.01);
00383 node_.param("resolution/orientation", res_orientation_, 0.001);
00384
00385
00386 sub_gains_ = node_.subscribe("gains", 5, &JTTaskController::setGains, this);
00387 sub_posture_ = node_.subscribe("command_posture", 5, &JTTaskController::commandPosture, this);
00388 sub_pose_ = node_.subscribe("command_pose", 1, &JTTaskController::commandPose, this);
00389
00390 StateMsg state_template;
00391 state_template.header.frame_id = root_name_;
00392 state_template.x.header.frame_id = root_name_;
00393 state_template.x_desi.header.frame_id = root_name_;
00394 state_template.x_desi_filtered.header.frame_id = root_name_;
00395 state_template.tau_pose.resize(Joints);
00396 state_template.tau_posture.resize(Joints);
00397 state_template.tau.resize(Joints);
00398 state_template.J.layout.dim.resize(2);
00399 state_template.J.data.resize(6*Joints);
00400 state_template.N.layout.dim.resize(2);
00401 state_template.N.data.resize(Joints*Joints);
00402 pub_state_.initialize(node_.advertise<StateMsg>("state", 10), 10, state_template);
00403
00404 geometry_msgs::PoseStamped pose_template;
00405 pose_template.header.frame_id = root_name_;
00406 pub_x_.initialize(node_.advertise<geometry_msgs::PoseStamped>("state/x", 10),
00407 10, pose_template);
00408 pub_x_desi_.initialize(node_.advertise<geometry_msgs::PoseStamped>("state/x_desi", 10),
00409 10, pose_template);
00410 pub_x_err_.initialize(node_.advertise<geometry_msgs::Twist>("state/x_err", 10),
00411 10, geometry_msgs::Twist());
00412 pub_xd_.initialize(node_.advertise<geometry_msgs::Twist>("state/xd", 10),
00413 10, geometry_msgs::Twist());
00414 pub_xd_desi_.initialize(node_.advertise<geometry_msgs::Twist>("state/xd_desi", 10),
00415 10, geometry_msgs::Twist());
00416 pub_wrench_.initialize(node_.advertise<geometry_msgs::Twist>("state/wrench", 10),
00417 10, geometry_msgs::Twist());
00418
00419 std_msgs::Float64MultiArray joints_template;
00420 joints_template.layout.dim.resize(1);
00421 joints_template.layout.dim[0].size = Joints;
00422 joints_template.layout.dim[0].stride = 1;
00423 joints_template.data.resize(7);
00424 pub_tau_.initialize(node_.advertise<std_msgs::Float64MultiArray>("state/tau", 10),
00425 10, joints_template);
00426
00427 return true;
00428 }
00429
00430 void JTTaskController::starting()
00431 {
00432
00433
00434
00435 JointVec q;
00436 chain_.getPositions(q);
00437 kin_->fk(q, x_desi_);
00438 x_desi_filtered_ = x_desi_;
00439 last_pose_ = x_desi_;
00440 q_posture_ = q;
00441 qdot_filtered_.setZero();
00442 last_wrench_.setZero();
00443
00444 last_stiffness_ = 0;
00445 last_compliance_ = 0;
00446 last_Dx_ = 0;
00447 last_Df_ = 0;
00448
00449 loop_count_ = 0;
00450 }
00451
00452
00453 static void computePoseError(const Eigen::Affine3d &xact, const Eigen::Affine3d &xdes, Eigen::Matrix<double,6,1> &err)
00454 {
00455 err.head<3>() = xact.translation() - xdes.translation();
00456 err.tail<3>() = 0.5 * (xdes.linear().col(0).cross(xact.linear().col(0)) +
00457 xdes.linear().col(1).cross(xact.linear().col(1)) +
00458 xdes.linear().col(2).cross(xact.linear().col(2)));
00459 }
00460
00461 void JTTaskController::update()
00462 {
00463
00464 ros::Time time = robot_state_->getTime();
00465 ros::Duration dt = time - last_time_;
00466 last_time_ = time;
00467 ++loop_count_;
00468
00469
00470
00471 JointVec q;
00472 chain_.getPositions(q);
00473
00474 Eigen::Affine3d x;
00475 kin_->fk(q, x);
00476
00477 Jacobian J;
00478 kin_->jac(q, J);
00479
00480
00481 JointVec qdot_raw;
00482 chain_.getVelocities(qdot_raw);
00483 for (int i = 0; i < Joints; ++i)
00484 qdot_filtered_[i] += joint_vel_filter_ * (qdot_raw[i] - qdot_filtered_[i]);
00485 JointVec qdot = qdot_filtered_;
00486 CartVec xdot = J * qdot;
00487
00488
00489
00490 {
00491 Eigen::Vector3d p0(x_desi_filtered_.translation());
00492 Eigen::Vector3d p1(x_desi_.translation());
00493 Eigen::Quaterniond q0(x_desi_filtered_.linear());
00494 Eigen::Quaterniond q1(x_desi_.linear());
00495 q0.normalize();
00496 q1.normalize();
00497
00498 tf::Quaternion tf_q0(q0.x(), q0.y(), q0.z(), q0.w());
00499 tf::Quaternion tf_q1(q1.x(), q1.y(), q1.z(), q1.w());
00500 tf::Quaternion tf_q = tf_q0.slerp(tf_q1, pose_command_filter_);
00501
00502 Eigen::Vector3d p = p0 + pose_command_filter_ * (p1 - p0);
00503
00504 Eigen::Quaterniond q(tf_q.w(), tf_q.x(), tf_q.y(), tf_q.z());
00505
00506 x_desi_filtered_ = Eigen::Translation3d(p) * q;
00507 }
00508 CartVec x_err;
00509
00510 computePoseError(x, x_desi_filtered_, x_err);
00511
00512 if(use_tip_frame_)
00513 {
00514 St <<
00515 x(0,0),x(0,1),x(0,2),0,0,0,
00516 x(1,0),x(1,1),x(1,2),0,0,0,
00517 x(2,0),x(2,1),x(2,2),0,0,0,
00518 0,0,0,x(0,0),x(0,1),x(0,2),
00519 0,0,0,x(1,0),x(1,1),x(1,2),
00520 0,0,0,x(2,0),x(2,1),x(2,2);
00521 St.transposeInPlace();
00522 }
00523
00524
00525 CartVec xdot_desi = (Kp.array() / Kd.array()) * (St * x_err).array() * -1.0;
00526
00527
00528 if (vel_saturation_trans_ > 0.0)
00529 {
00530 if (fabs(xdot_desi.head<3>().norm()) > vel_saturation_trans_)
00531 xdot_desi.head<3>() *= (vel_saturation_trans_ / xdot_desi.head<3>().norm());
00532 }
00533 if (vel_saturation_rot_ > 0.0)
00534 {
00535 if (fabs(xdot_desi.tail<3>().norm()) > vel_saturation_rot_)
00536 xdot_desi.tail<3>() *= (vel_saturation_rot_ / xdot_desi.tail<3>().norm());
00537 }
00538
00539 CartVec F = Kd.array() * (xdot_desi.array() - (St * xdot).array());
00540
00541
00542 JointVec tau_pose = J.transpose() * St.transpose() * F;
00543
00544
00545
00546
00547 Eigen::Matrix<double,6,6> I6; I6.setIdentity();
00548 Eigen::Matrix<double,6,6> JJt = J * J.transpose();
00549 Eigen::Matrix<double,6,6> JJt_inv;
00550 JJt_inv = JJt.inverse();
00551 Eigen::Matrix<double,6,6> JJt_damped = J * J.transpose() + jacobian_inverse_damping_ * I6;
00552 Eigen::Matrix<double,6,6> JJt_inv_damped;
00553 JJt_inv_damped = JJt_damped.inverse();
00554 Eigen::Matrix<double,Joints,6> J_pinv = J.transpose() * JJt_inv_damped;
00555
00556
00557 Eigen::Matrix<double,Joints,Joints> I;
00558 I.setIdentity();
00559 Eigen::Matrix<double,Joints,Joints> N = I - J_pinv * J;
00560
00561
00562
00563
00564 JointVec tau_posture;
00565 tau_posture.setZero();
00566 if (use_posture_)
00567 {
00568 JointVec posture_err = q_posture_ - q;
00569 for (size_t j = 0; j < Joints; ++j)
00570 {
00571 if (chain_.getJoint(j)->joint_->type == urdf::Joint::CONTINUOUS)
00572 posture_err[j] = angles::normalize_angle(posture_err[j]);
00573 }
00574
00575 for (size_t j = 0; j < Joints; ++j) {
00576 if (fabs(q_posture_[j] - 9999) < 1e-5)
00577 posture_err[j] = 0.0;
00578 }
00579
00580 JointVec qdd_posture = k_posture_ * posture_err;
00581 tau_posture = joint_dd_ff_.array() * (N * qdd_posture).array();
00582 }
00583
00584 JointVec tau = tau_pose + tau_posture;
00585
00586
00587 double sat_scaling = 1.0;
00588 for (int i = 0; i < Joints; ++i) {
00589 if (saturation_[i] > 0.0)
00590 sat_scaling = std::min(sat_scaling, fabs(saturation_[i] / tau[i]));
00591 }
00592 JointVec tau_sat = sat_scaling * tau;
00593
00594 chain_.addEfforts(tau_sat);
00595
00596
00597
00598
00599 CartVec df = F - last_wrench_;
00600 CartVec dx;
00601 computePoseError(last_pose_, x, dx);
00602
00603
00604
00605 double Df, Dx;
00606 if (fabs(dx[2]) >= res_position_)
00607 Df = df[2] * res_position_ / fabs(dx[2]);
00608 else
00609 Df = (1. - fabs(dx[2])/res_position_) * last_Df_ + df[2];
00610 if (fabs(df[2]) >= res_force_)
00611 Dx = dx[2] * res_force_ / fabs(df[2]);
00612 else
00613 Dx = (1. - fabs(df[2])/res_force_) * last_Dx_ + dx[2];
00614 last_Df_ = Df;
00615 last_Dx_ = Dx;
00616
00617 double stiffness, compliance;
00618 if (fabs(dx[2]) >= res_position_)
00619 stiffness = fabs(df[2]) / fabs(dx[2]);
00620 else
00621 stiffness = (1 - fabs(dx[2])/res_position_) * last_stiffness_ + fabs(df[2]) / res_position_;
00622 if (fabs(df[2]) >= res_force_)
00623 compliance = fabs(dx[2]) / fabs(df[2]);
00624 else
00625 compliance = (1 - fabs(df[2])/res_force_) * last_compliance_ + fabs(dx[2]) / res_force_;
00626
00627 last_pose_ = x;
00628 last_wrench_ = F;
00629 last_stiffness_ = stiffness;
00630 last_compliance_ = compliance;
00631
00632 if (loop_count_ % 10 == 0)
00633 {
00634 geometry_msgs::PoseStamped::Ptr pose_msg;
00635 geometry_msgs::Twist::Ptr twist_msg;
00636 std_msgs::Float64MultiArray::Ptr q_msg;
00637
00638 if (pose_msg = pub_x_.allocate()) {
00639 pose_msg->header.stamp = time;
00640 tf::poseEigenToMsg(x, pose_msg->pose);
00641 pub_x_.publish(pose_msg);
00642 }
00643
00644 if (pose_msg = pub_x_desi_.allocate()) {
00645 pose_msg->header.stamp = time;
00646 tf::poseEigenToMsg(x_desi_, pose_msg->pose);
00647 pub_x_desi_.publish(pose_msg);
00648 }
00649
00650 if (twist_msg = pub_x_err_.allocate()) {
00651 tf::twistEigenToMsg(x_err, *twist_msg);
00652 pub_x_err_.publish(twist_msg);
00653 }
00654
00655 if (twist_msg = pub_xd_.allocate()) {
00656 tf::twistEigenToMsg(xdot, *twist_msg);
00657 pub_xd_.publish(twist_msg);
00658 }
00659
00660 if (twist_msg = pub_xd_desi_.allocate()) {
00661 tf::twistEigenToMsg(xdot_desi, *twist_msg);
00662 pub_xd_desi_.publish(twist_msg);
00663 }
00664
00665 if (twist_msg = pub_wrench_.allocate()) {
00666 tf::twistEigenToMsg(F, *twist_msg);
00667 pub_wrench_.publish(twist_msg);
00668 }
00669
00670 if (q_msg = pub_tau_.allocate()) {
00671 for (size_t i = 0; i < Joints; ++i)
00672 q_msg->data[i] = tau[i];
00673 pub_tau_.publish(q_msg);
00674 }
00675
00676 StateMsg::Ptr state_msg;
00677 if (state_msg = pub_state_.allocate()) {
00678 state_msg->header.stamp = time;
00679 state_msg->x.header.stamp = time;
00680 tf::poseEigenToMsg(x, state_msg->x.pose);
00681 state_msg->x_desi.header.stamp = time;
00682 tf::poseEigenToMsg(x_desi_, state_msg->x_desi.pose);
00683 state_msg->x_desi_filtered.header.stamp = time;
00684 tf::poseEigenToMsg(x_desi_filtered_, state_msg->x_desi_filtered.pose);
00685 tf::twistEigenToMsg(x_err, state_msg->x_err);
00686 tf::twistEigenToMsg(xdot, state_msg->xd);
00687 tf::twistEigenToMsg(xdot_desi, state_msg->xd_desi);
00688 tf::wrenchEigenToMsg(F, state_msg->F);
00689 tf::matrixEigenToMsg(J, state_msg->J);
00690 tf::matrixEigenToMsg(N, state_msg->N);
00691 for (size_t j = 0; j < Joints; ++j) {
00692 state_msg->tau_pose[j] = tau_pose[j];
00693 state_msg->tau_posture[j] = tau_posture[j];
00694 state_msg->tau[j] = tau[j];
00695 }
00696 state_msg->stiffness = stiffness;
00697 state_msg->compliance = compliance;
00698 state_msg->Df = Df / res_position_;
00699 state_msg->Dx = Dx / res_force_;
00700 state_msg->df = df[2];
00701 state_msg->dx = dx[2];
00702 pub_state_.publish(state_msg);
00703 }
00704 }
00705 }
00706
00707 }
00708
00709 PLUGINLIB_REGISTER_CLASS(JTTaskController, pr2_teleop::JTTaskController, pr2_controller_interface::Controller)
00710