51 JTCartesianController::JTCartesianController()
    52   : robot_state_(NULL), use_posture_(false)
    70     ROS_ERROR(
"JTCartesianController: No root name found on parameter server (namespace: %s)",
    75     ROS_ERROR(
"JTCartesianController: No tip name found on parameter server (namespace: %s)",
    94     ROS_ERROR(
"The JTCartesianController works with %d joints, but the chain from %s to %s has %d joints.",
   105   double kp_trans, kd_trans, kp_rot, kd_rot;
   118   Kp << kp_trans, kp_trans, kp_trans,  kp_rot, kp_rot, kp_rot;
   119   Kd << kd_trans, kd_trans, kd_trans,  kd_rot, kd_rot, kd_rot;
   131   for (
int i = 0; i < 
Joints; ++i)
   133   for (
int i = 0; i < 
Joints; ++i)
   151   state_template.x.header.frame_id = 
root_name_;
   152   state_template.x_desi.header.frame_id = 
root_name_;
   153   state_template.x_desi_filtered.header.frame_id = 
root_name_;
   154   state_template.tau_pose.resize(Joints);
   155   state_template.tau_posture.resize(Joints);
   156   state_template.tau.resize(Joints);
   157   state_template.J.layout.dim.resize(2);
   158   state_template.J.data.resize(6*Joints);
   159   state_template.N.layout.dim.resize(2);
   160   state_template.N.data.resize(Joints*Joints);
   192 static void computePoseError(
const Eigen::Affine3d &xact, 
const Eigen::Affine3d &xdes, Eigen::Matrix<double,6,1> &err)
   194   err.head<3>() = xact.translation() - xdes.translation();
   195   err.tail<3>()   = 0.5 * (xdes.linear().col(0).cross(xact.linear().col(0)) +
   196                           xdes.linear().col(1).cross(xact.linear().col(1)) +
   197                           xdes.linear().col(2).cross(xact.linear().col(2)));
   222   for (
int i = 0; i < 
Joints; ++i)
   231     Eigen::Vector3d p1(
x_desi_.translation());
   233     Eigen::Quaterniond q1(
x_desi_.linear());
   243     Eigen::Quaterniond q(tf_q.w(), tf_q.x(), tf_q.y(), tf_q.z());
   251   CartVec xdot_desi = (
Kp.array() / 
Kd.array()) * x_err.array() * -1.0;
   265   CartVec F = 
Kd.array() * (xdot_desi - xdot).array();
   267   JointVec tau_pose = J.transpose() * F;
   272   Eigen::Matrix<double,6,6> I6; I6.setIdentity();
   276   Eigen::Matrix<double,6,6> JJt_inv_damped = JJt_damped.inverse();
   277   Eigen::Matrix<double,Joints,6> J_pinv = J.transpose() * JJt_inv_damped;
   280   Eigen::Matrix<double,Joints,Joints> I;
   282   Eigen::Matrix<double,Joints,Joints> N = I - J_pinv * J;
   288   tau_posture.setZero();
   292     for (
size_t j = 0; j < 
Joints; ++j)
   298     for (
size_t j = 0; j < 
Joints; ++j) {
   300         posture_err[j] = 0.0;
   304     tau_posture = 
joint_dd_ff_.array() * (N * qdd_posture).array();
   307   JointVec tau = tau_pose + tau_posture;
   310   double sat_scaling = 1.0;
   311   for (
int i = 0; i < 
Joints; ++i) {
   313       sat_scaling = std::min(sat_scaling, fabs(
saturation_[i] / tau[i]));
   315   JointVec tau_sat = sat_scaling * tau;
   341       for (
size_t j = 0; j < 
Joints; ++j) {
 PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void twistEigenToMsg(const Eigen::Matrix< double, 6, 1 > &e, geometry_msgs::Twist &m)
void getPositions(std::vector< double > &)
double vel_saturation_trans_
realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > pub_x_desi_
void commandPosture(const std_msgs::Float64MultiArray::ConstPtr &msg)
double jacobian_inverse_damping_
static void computePoseError(const Eigen::Affine3d &xact, const Eigen::Affine3d &xdes, Eigen::Matrix< double, 6, 1 > &err)
pr2_mechanism_model::Chain chain_
realtime_tools::RealtimePublisher< StateMsg > pub_state_
double pose_command_filter_
Eigen::Matrix< double, 6, 1 > Kp
boost::shared_ptr< const urdf::Joint > joint_
Eigen::Matrix< double, 6, 1 > Kd
void getVelocities(std::vector< double > &)
Quaternion slerp(const Quaternion &q, const tfScalar &t) const 
void setGains(const std_msgs::Float64MultiArray::ConstPtr &msg)
Eigen::Affine3d last_pose_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
ros::Subscriber sub_gains_
Eigen::Matrix< double, 6, 1 > CartVec
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
double vel_saturation_rot_
void matrixEigenToMsg(const Eigen::MatrixBase< Derived > &e, std_msgs::Float64MultiArray &m)
const std::string & getNamespace() const 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
def normalize_angle(angle)
JointState * getJoint(unsigned int actuated_joint_i)
Eigen::Matrix< double, Joints, 1 > JointVec
ros::Subscriber sub_posture_
void wrenchEigenToMsg(const Eigen::Matrix< double, 6, 1 > &e, geometry_msgs::Wrench &m)
bool getParam(const std::string &key, std::string &s) const 
Eigen::Matrix< double, 6, Joints > Jacobian
ros::Subscriber sub_pose_
bool init(RobotState *robot_state, const std::string &root, const std::string &tip)
robot_mechanism_controllers::JTCartesianControllerState StateMsg
pr2_mechanism_model::RobotState * robot_state_
boost::scoped_ptr< Kin< Joints > > kin_
void toKDL(KDL::Chain &chain)
Eigen::Affine3d x_desi_filtered_
void addEfforts(KDL::JntArray &)
void commandPose(const geometry_msgs::PoseStamped::ConstPtr &command)