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