6 : chain_base_link_(chain_base_link), nh_(nh)
10 throw std::runtime_error(
11 "ERROR getting robot description (/robot_description)");
23 ROS_WARN(
"KDLManager: Missing eps parameter, setting default");
29 ROS_WARN(
"KDLManager: Missing max_tf_attempts parameter, setting default");
35 ROS_WARN(
"KDLManager: Missing ikvel_solver parameter, setting default");
42 "KDLManager: Missing ik_angle_tolerance parameter, setting default");
48 ROS_WARN(
"KDLManager: Missing ik_pos_tolerance parameter, setting default");
65 ROS_WARN(
"KDLManager: Missing nso_weight parameter, setting default");
70 std::vector<double> gravity;
71 if (!
nh_.
getParam(
"kdl_manager/gravity_in_base_link", gravity))
74 "KDLManager: Missing kdl_manager/gravity_in_base_link parameter. This " 75 "will affect the dynamic solvers");
80 if (gravity.size() != 3)
83 << gravity.size() <<
". Should have size 3");
115 unsigned int joint_n =
chain_.at(end_effector_link).getNrOfJoints();
120 "Number of joints for kinematic chain is smaller than 6 (%d). The " 121 "NSO ik solver vel has issues with under-actuated chains. Using WDLS",
129 q_vel_lim(joint_n), q_desired(joint_n);
132 for (
unsigned int i = 0; i < joint_n; i++)
135 q_desired(i) = (q_max(i) + q_min(i)) / 2;
138 ikvel_[end_effector_link] =
140 chain_.at(end_effector_link), q_desired,
w,
eps_));
149 return (
chain_.find(end_effector_link) !=
chain_.end());
158 <<
", but it was already initialized");
171 <<
"> in the kinematic tree");
176 chain_[end_effector_link] = chain;
179 std::vector<std::string> new_vector;
193 new_vector.push_back(kdl_joint.
getName());
199 fkpos_[end_effector_link] =
201 fkvel_[end_effector_link] =
203 ikpos_[end_effector_link] =
216 const std::string &gripping_point_frame)
226 eef_to_gripping_point))
232 eef_to_gripping_point.
Inverse();
237 const std::string &sensor_point_frame)
247 eef_to_sensor_point))
257 const Eigen::VectorXd &qdot,
258 sensor_msgs::JointState &state)
const 265 if (
chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
268 "Joint chain for eef %s has a different number of joints than the " 270 end_effector_link.c_str());
274 Eigen::VectorXd q(
chain_.at(end_effector_link).getNrOfJoints());
277 for (
unsigned long i = 0; i < state.name.size(); i++)
281 q[joint_index] = state.position[i];
285 if (joint_index ==
chain_.at(end_effector_link).getNrOfJoints())
291 if (joint_index !=
chain_.at(end_effector_link).getNrOfJoints())
294 "Provided joint state does not have all of the required chain joints");
302 const Eigen::VectorXd &q,
303 const Eigen::VectorXd &qdot,
304 sensor_msgs::JointState &state)
const 306 if (q.rows() != qdot.rows())
309 "Given joint state with a different number of joint positions and " 319 if (
chain_.at(end_effector_link).getNrOfJoints() != qdot.rows())
322 "Joint chain for eef %s has a different number of joints than the " 324 end_effector_link.c_str());
330 for (
unsigned long i = 0;
334 for (
unsigned long j = 0; j < state.name.size(); j++)
338 state.position[j] = q[i];
339 state.velocity[j] = qdot[i];
349 <<
" from given joint state");
358 const Eigen::VectorXd &q,
359 const Eigen::VectorXd &qdot,
360 const Eigen::VectorXd &effort,
361 sensor_msgs::JointState &state)
const 373 if (
chain_.at(end_effector_link).getNrOfJoints() != effort.rows())
377 <<
" has a different number of joints than the provided");
382 for (
unsigned long i = 0;
386 for (
unsigned long j = 0; j < state.name.size(); j++)
390 state.effort[j] = effort[i];
400 <<
" from given joint state");
409 const sensor_msgs::JointState &state,
418 if (!
getEefPose(end_effector_link, state, eef_pose))
428 const sensor_msgs::JointState &state,
437 if (!
getEefPose(end_effector_link, state, eef_pose))
447 const sensor_msgs::JointState &state,
462 if (!
getEefPose(end_effector_link, state, eef_pose))
468 if (!
getEefTwist(end_effector_link, state, eef_twist))
473 Eigen::Vector3d vel_eig, rot_eig, converted_vel, r_eig;
483 out.
vel =
KDL::Vector(converted_vel[0], converted_vel[1], converted_vel[2]);
490 const sensor_msgs::JointState &state,
506 fkpos_.at(end_effector_link)->JntToCart(positions, out);
511 const sensor_msgs::JointState &state,
526 fkvel_.at(end_effector_link)->JntToCart(velocities, out);
539 unsigned int joint_n =
chain_.at(end_effector_link).getNrOfJoints();
540 if (q_min.
rows() != joint_n || q_max.
rows() != joint_n ||
541 q_vel_lim.
rows() != joint_n)
544 "KDLManager::getJointPositionLimits requires initialized joint arrays");
548 urdf::JointConstSharedPtr joint;
549 urdf::JointLimitsSharedPtr limits;
553 for (
unsigned int i = 0; i <
chain_.at(end_effector_link).getNrOfSegments();
556 if (
chain_.at(end_effector_link).getSegment(i).getJoint().getType() ==
557 KDL::Joint::JointType::None)
563 chain_.at(end_effector_link).getSegment(i).getJoint().getName());
564 limits = joint->limits;
565 q_min(j) = limits->lower;
566 q_max(j) = limits->upper;
567 q_vel_lim(j) = limits->velocity;
575 const sensor_msgs::JointState &state,
594 const sensor_msgs::JointState &state,
595 Eigen::VectorXd &q)
const 614 const sensor_msgs::JointState &state,
622 q_dot.
resize(
chain_.at(end_effector_link).getNrOfJoints());
635 const sensor_msgs::JointState &state,
644 KDL::JntSpaceInertiaMatrix B(
chain_.at(end_effector_link).getNrOfJoints());
652 const sensor_msgs::JointState &state,
676 const sensor_msgs::JointState &state,
677 Eigen::MatrixXd &coriolis)
692 dynamic_chain_.at(end_effector_link)->JntToCoriolis(q, q_dot.qdot, cor);
698 const std::string &target_frame,
701 geometry_msgs::PoseStamped base_to_target;
702 base_to_target.header.frame_id = base_frame;
703 base_to_target.header.stamp =
ros::Time(0);
704 base_to_target.pose.position.x = 0;
705 base_to_target.pose.position.y = 0;
706 base_to_target.pose.position.z = 0;
707 base_to_target.pose.orientation.x = 0;
708 base_to_target.pose.orientation.y = 0;
709 base_to_target.pose.orientation.z = 0;
710 base_to_target.pose.orientation.w = 1;
722 ROS_WARN(
"TF exception in kdl manager: %s", ex.what());
727 if (attempts >= max_tf_attempts_)
730 "KDL manager could not find the transform between frames %s and %s",
731 base_frame.c_str(), target_frame.c_str());
747 sensor_msgs::JointState dummy_state;
749 for (
unsigned int i = 0;
753 dummy_state.position.push_back(0);
754 dummy_state.velocity.push_back(0);
755 dummy_state.effort.push_back(0);
759 if (
getPoseIK(end_effector_link, dummy_state, in, dummy_out))
768 const sensor_msgs::JointState &state,
784 out.
resize(
chain_.at(end_effector_link).getNrOfJoints());
785 ikpos_.at(end_effector_link)->CartToJnt(positions, in, out);
790 difference = computedPose.Inverse() * in;
791 Eigen::Vector3d quat_v;
794 difference.
M.
GetQuaternion(quat_v[0], quat_v[1], quat_v[2], quat_w);
795 double angle = 2 *
atan2(quat_v.norm(), quat_w);
800 "KDL manager could not compute pose ik for end-effector %s. Final " 801 "orientation error was %.2f",
802 end_effector_link.c_str(), angle);
809 "KDL manager could not compute pose ik for end-effector %s. Final " 810 "position error was %.2f",
811 end_effector_link.c_str(), difference.p.Norm());
819 const sensor_msgs::JointState &state,
831 return getPoseIK(end_effector_link, state, pose_in_eef, out);
835 const sensor_msgs::JointState &state,
843 fkpos_.at(end_effector_link)->JntToCart(in, out);
848 const sensor_msgs::JointState &state,
865 if (!
getEefPose(end_effector_link, state, peef))
871 Eigen::Vector3d vel_eig, rot_eig, peef_eig, pgrip_eig;
872 modified_in = pgrip.
M * in;
884 if (!
getVelIK(end_effector_link, state, modified_in, out))
893 const sensor_msgs::JointState &state,
908 out.
resize(
chain_.at(end_effector_link).getNrOfJoints());
909 ikvel_.at(end_effector_link)->CartToJnt(positions, in, out);
914 const sensor_msgs::JointState &state,
929 out.
resize(positions.rows());
930 jac_solver_.at(end_effector_link)->JntToJac(positions, out);
935 const sensor_msgs::JointState &state)
const 942 unsigned int processed_joints = 0, name_size, pos_size, vel_size;
943 name_size = state.name.size();
944 pos_size = state.position.size();
945 vel_size = state.velocity.size();
947 if (name_size != pos_size || name_size != vel_size)
950 "Got joint state where the name, position and velocity dimensions " 951 "(resp. %d, %d, %d) are different",
952 name_size, pos_size, vel_size);
956 for (
unsigned long i = 0;
959 for (
unsigned long j = 0; j < state.name.size(); j++)
977 const sensor_msgs::JointState ¤t_state,
978 const std::string &end_effector_link,
KDL::JntArray &positions,
981 unsigned int processed_joints = 0;
982 unsigned int name_size, pos_size, vel_size;
984 name_size = current_state.name.size();
985 pos_size = current_state.position.size();
986 vel_size = current_state.velocity.size();
988 if (name_size != pos_size || name_size != vel_size)
991 "Got joint state where the name, position and velocity dimensions " 992 "(resp. %d, %d, %d) are different",
993 name_size, pos_size, vel_size);
997 for (
unsigned long i = 0;
1000 for (
unsigned long j = 0; j < current_state.name.size(); j++)
1003 current_state.name[j])
1005 positions(processed_joints) = current_state.position[j];
1006 velocities.
q(processed_joints) = current_state.position[j];
1007 velocities.
qdot(processed_joints) = current_state.velocity[j];
1015 ROS_ERROR(
"Failed to acquire chain joint state");
1023 const std::string &joint_name)
const 1027 if (chain.
segments[i].getJoint().getName() == joint_name)
1037 unsigned int &num_joints)
const 1044 num_joints =
chain_.at(end_effector_link).getNrOfJoints();
1048 bool setKDLManager(
const ArmInfo &arm_info, std::shared_ptr<KDLManager> manager)
1050 if (!manager->initializeArm(arm_info.kdl_eef_frame))
1055 if (!manager->setGrippingPoint(arm_info.kdl_eef_frame,
1056 arm_info.gripping_frame))
1062 "Successfully set up arm %s with eef_frame %s and gripping_frame %s",
1063 arm_info.name.c_str(), arm_info.kdl_eef_frame.c_str(),
1064 arm_info.gripping_frame.c_str());
const Segment & getSegment(unsigned int nr) const
const std::string WDLS_SOLVER("wdls")
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
unsigned int rows() const
void resize(unsigned int newNrOfColumns)
const std::string NSO_SOLVER("nso")
unsigned int getNrOfSegments() const
IMETHOD Twist GetTwist() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void GetQuaternion(double &x, double &y, double &z, double &w) const
const std::string & getName() const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
const Joint & getJoint() const
URDF_EXPORT bool initParam(const std::string ¶m)
void vectorEigenToKDL(const Eigen::Matrix< double, 3, 1 > &e, KDL::Vector &k)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
void resize(unsigned int newSize)
TFSIMD_FORCE_INLINE const tfScalar & w() const
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
void vectorKDLToEigen(const KDL::Vector &k, Eigen::Matrix< double, 3, 1 > &e)
bool getParam(const std::string &key, std::string &s) const
std::vector< Segment > segments
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
const std::string getTypeName() const
#define ROS_ERROR_STREAM(args)