34 KDL::Jacobian jac_full;
37 Eigen::Matrix<double, 6, Eigen::Dynamic> jac_ext;
42 Eigen::Quaterniond quat_cb;
44 Eigen::Matrix3d rot_cb = quat_cb.toRotationMatrix();
48 Eigen::Vector3d w_x_eb(1, 0, 0);
49 Eigen::Vector3d w_y_eb(0, 1, 0);
50 Eigen::Vector3d w_z_eb(0, 0, 1);
53 Eigen::Vector3d w_x_cb = quat_cb * w_x_eb;
54 Eigen::Vector3d w_y_cb = quat_cb * w_y_eb;
55 Eigen::Vector3d w_z_cb = quat_cb * w_z_eb;
59 Eigen::Vector3d p_eb(eb_frame_ct.p.x(), eb_frame_ct.p.y(), eb_frame_ct.p.z());
62 Eigen::Vector3d p_cb = quat_cb * p_eb;
65 Eigen::Vector3d vel_x_cb = w_x_cb.cross(p_cb);
66 Eigen::Vector3d vel_y_cb = w_y_cb.cross(p_cb);
67 Eigen::Vector3d vel_z_cb = w_z_cb.cross(p_cb);
71 jac_ext(0, 0) = rot_cb(0, 0) * active_dim.
lin_x;
72 jac_ext(1, 0) = rot_cb(1, 0) * active_dim.
lin_x;
73 jac_ext(2, 0) = rot_cb(2, 0) * active_dim.
lin_x;
79 jac_ext(0, 1) = rot_cb(0, 1) * active_dim.
lin_y;
80 jac_ext(1, 1) = rot_cb(1, 1) * active_dim.
lin_y;
81 jac_ext(2, 1) = rot_cb(2, 1) * active_dim.
lin_y;
87 jac_ext(0, 2) = rot_cb(0, 2) * active_dim.
lin_z;
88 jac_ext(1, 2) = rot_cb(1, 2) * active_dim.
lin_z;
89 jac_ext(2, 2) = rot_cb(2, 2) * active_dim.
lin_z;
95 jac_ext(0, 3) = vel_x_cb(0) * active_dim.
rot_x;
96 jac_ext(1, 3) = vel_x_cb(1) * active_dim.
rot_x;
97 jac_ext(2, 3) = vel_x_cb(2) * active_dim.
rot_x;
98 jac_ext(3, 3) = w_x_cb(0) * active_dim.
rot_x;
99 jac_ext(4, 3) = w_x_cb(1) * active_dim.
rot_x;
100 jac_ext(5, 3) = w_x_cb(2) * active_dim.
rot_x;
103 jac_ext(0, 4) = vel_y_cb(0) * active_dim.
rot_y;
104 jac_ext(1, 4) = vel_y_cb(1) * active_dim.
rot_y;
105 jac_ext(2, 4) = vel_y_cb(2) * active_dim.
rot_y;
106 jac_ext(3, 4) = w_y_cb(0) * active_dim.
rot_y;
107 jac_ext(4, 4) = w_y_cb(1) * active_dim.
rot_y;
108 jac_ext(5, 4) = w_y_cb(2) * active_dim.
rot_y;
111 jac_ext(0, 5) = vel_z_cb(0) * active_dim.
rot_z;
112 jac_ext(1, 5) = vel_z_cb(1) * active_dim.
rot_z;
113 jac_ext(2, 5) = vel_z_cb(2) * active_dim.
rot_z;
114 jac_ext(3, 5) = w_z_cb(0) * active_dim.
rot_z;
115 jac_ext(4, 5) = w_z_cb(1) * active_dim.
rot_z;
116 jac_ext(5, 5) = w_z_cb(2) * active_dim.
rot_z;
123 jac_full_matrix.resize(6, jac_chain.data.cols() + jac_ext.cols());
124 jac_full_matrix << jac_chain.data, jac_ext;
125 jac_full.resize(jac_chain.data.cols() + jac_ext.cols());
126 jac_full.data << jac_full_matrix;
149 for (
unsigned int i = 0; i <
ext_dof_; i++)
151 limits_max_.push_back(std::numeric_limits<double>::max());
152 limits_min_.push_back(-std::numeric_limits<double>::max());
161 limits_acc_.push_back(std::numeric_limits<double>::max());
173 KDL::Frame bl_frame_ct, cb_frame_bl;
198 active_dim.
lin_x = 1;
199 active_dim.
lin_y = 1;
200 active_dim.
lin_z = 0;
202 active_dim.
rot_x = 0;
203 active_dim.
rot_y = 0;
204 active_dim.
rot_z = 1;
215 unsigned int chain_dof = joint_states.
current_q_.rows();
221 for (
unsigned int i = 0; i< chain_dof; i++)
228 for (
unsigned int i = 0; i <
ext_dof_; i++)
231 js.
last_q_(chain_dof + i) = 0.0;
244 for (
unsigned int i = 0; i <
ext_dof_; i++)
246 lp.
limits_max.push_back(std::numeric_limits<double>::max());
247 lp.
limits_min.push_back(-std::numeric_limits<double>::max());
256 lp.
limits_acc.push_back(std::numeric_limits<double>::max());
266 geometry_msgs::Twist base_vel_msg;