1 #ifndef __KDL_MANAGER__ 2 #define __KDL_MANAGER__ 6 #include <generic_control_toolbox/ArmInfo.h> 7 #include <geometry_msgs/WrenchStamped.h> 10 #include <sensor_msgs/JointState.h> 15 #include <kdl/chaindynparam.hpp> 16 #include <kdl/chainfksolverpos_recursive.hpp> 17 #include <kdl/chainfksolvervel_recursive.hpp> 18 #include <kdl/chainiksolverpos_lma.hpp> 19 #include <kdl/chainiksolvervel_pinv_nso.hpp> 20 #include <kdl/chainiksolvervel_wdls.hpp> 21 #include <kdl/chainjnttojacsolver.hpp> 22 #include <kdl/frames.hpp> 23 #include <kdl/kdl.hpp> 59 bool isInitialized(
const std::string &end_effector_link)
const;
72 const sensor_msgs::JointState &state)
const;
83 const std::string &gripping_point_frame);
95 const std::string &sensor_point_frame);
107 const Eigen::VectorXd &qdot,
108 sensor_msgs::JointState &state)
const;
121 const Eigen::VectorXd &q,
const Eigen::VectorXd &qdot,
122 sensor_msgs::JointState &state)
const;
137 const Eigen::VectorXd &q,
const Eigen::VectorXd &qdot,
138 const Eigen::VectorXd &effort,
139 sensor_msgs::JointState &state)
const;
151 const sensor_msgs::JointState &state,
164 const sensor_msgs::JointState &state,
177 const sensor_msgs::JointState &state,
187 bool verifyPose(
const std::string &end_effector_link,
201 bool getPoseIK(
const std::string &end_effector_link,
202 const sensor_msgs::JointState &state,
const KDL::Frame &in,
217 const sensor_msgs::JointState &state,
230 bool getPoseFK(
const std::string &end_effector_link,
231 const sensor_msgs::JointState &state,
const KDL::JntArray &in,
245 const sensor_msgs::JointState &state,
258 bool getVelIK(
const std::string &end_effector_link,
259 const sensor_msgs::JointState &state,
const KDL::Twist &in,
270 bool getJacobian(
const std::string &end_effector_link,
271 const sensor_msgs::JointState &state,
282 bool getEefPose(
const std::string &end_effector_link,
283 const sensor_msgs::JointState &state,
KDL::Frame &out)
const;
293 bool getEefTwist(
const std::string &end_effector_link,
294 const sensor_msgs::JointState &state,
320 const sensor_msgs::JointState &state,
323 const sensor_msgs::JointState &state,
324 Eigen::VectorXd &q)
const;
335 const sensor_msgs::JointState &state,
346 bool getInertia(
const std::string &end_effector_link,
347 const sensor_msgs::JointState &state, Eigen::MatrixXd &H);
357 bool getGravity(
const std::string &end_effector_link,
358 const sensor_msgs::JointState &state, Eigen::MatrixXd &g);
368 bool getCoriolis(
const std::string &end_effector_link,
369 const sensor_msgs::JointState &state,
370 Eigen::MatrixXd &coriolis);
380 unsigned int &num_joints)
const;
396 std::map<std::string, IkSolverVelPtr>
ikvel_;
397 std::map<std::string, IkSolverPosPtr>
ikpos_;
398 std::map<std::string, FkSolverPosPtr>
fkpos_;
399 std::map<std::string, FkSolverVelPtr>
fkvel_;
403 std::map<std::string, KDL::Chain>
chain_;
410 std::map<std::string, std::vector<std::string> >
440 const std::string &target_frame,
456 const std::string &end_effector_link,
479 std::shared_ptr<KDLManager> manager);
490 std::shared_ptr<KDLManager> manager);
const std::string WDLS_SOLVER("wdls")
const std::string NSO_SOLVER("nso")