kdl_manager.hpp
Go to the documentation of this file.
1 #ifndef __KDL_MANAGER__
2 #define __KDL_MANAGER__
3 
6 #include <generic_control_toolbox/ArmInfo.h>
7 #include <geometry_msgs/WrenchStamped.h>
9 #include <ros/ros.h>
10 #include <sensor_msgs/JointState.h>
11 #include <tf/transform_listener.h>
12 #include <urdf/model.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>
25 #include <stdexcept>
26 
27 const std::string WDLS_SOLVER("wdls"), NSO_SOLVER("nso");
28 
30 {
35 class KDLManager : public ManagerBase
36 {
37  public:
38  KDLManager(const std::string &chain_base_link,
40  ~KDLManager();
41 
50  bool initializeArm(const std::string &end_effector_link);
51 
59  bool isInitialized(const std::string &end_effector_link) const;
60 
71  bool checkStateMessage(const std::string &end_effector_link,
72  const sensor_msgs::JointState &state) const;
82  bool setGrippingPoint(const std::string &end_effector_link,
83  const std::string &gripping_point_frame);
84 
94  bool setSensorPoint(const std::string &end_effector_link,
95  const std::string &sensor_point_frame);
96 
106  bool getJointState(const std::string &end_effector_link,
107  const Eigen::VectorXd &qdot,
108  sensor_msgs::JointState &state) const;
109 
120  bool getJointState(const std::string &end_effector_link,
121  const Eigen::VectorXd &q, const Eigen::VectorXd &qdot,
122  sensor_msgs::JointState &state) const;
123 
136  bool getJointState(const std::string &end_effector_link,
137  const Eigen::VectorXd &q, const Eigen::VectorXd &qdot,
138  const Eigen::VectorXd &effort,
139  sensor_msgs::JointState &state) const;
140 
150  bool getGrippingPoint(const std::string &end_effector_link,
151  const sensor_msgs::JointState &state,
152  KDL::Frame &out) const;
153 
163  bool getSensorPoint(const std::string &end_effector_link,
164  const sensor_msgs::JointState &state,
165  KDL::Frame &out) const;
166 
176  bool getGrippingTwist(const std::string &end_effector_link,
177  const sensor_msgs::JointState &state,
178  KDL::Twist &out) const;
179 
187  bool verifyPose(const std::string &end_effector_link,
188  const KDL::Frame &in) const;
189 
201  bool getPoseIK(const std::string &end_effector_link,
202  const sensor_msgs::JointState &state, const KDL::Frame &in,
203  KDL::JntArray &out) const;
204 
216  bool getGrippingPoseIK(const std::string &end_effector_link,
217  const sensor_msgs::JointState &state,
218  const KDL::Frame &in, KDL::JntArray &out) const;
219 
230  bool getPoseFK(const std::string &end_effector_link,
231  const sensor_msgs::JointState &state, const KDL::JntArray &in,
232  KDL::Frame &out) const;
233 
244  bool getGrippingVelIK(const std::string &end_effector_link,
245  const sensor_msgs::JointState &state,
246  const KDL::Twist &in, KDL::JntArray &out) const;
247 
258  bool getVelIK(const std::string &end_effector_link,
259  const sensor_msgs::JointState &state, const KDL::Twist &in,
260  KDL::JntArray &out) const;
261 
270  bool getJacobian(const std::string &end_effector_link,
271  const sensor_msgs::JointState &state,
272  KDL::Jacobian &out) const;
273 
282  bool getEefPose(const std::string &end_effector_link,
283  const sensor_msgs::JointState &state, KDL::Frame &out) const;
284 
293  bool getEefTwist(const std::string &end_effector_link,
294  const sensor_msgs::JointState &state,
295  KDL::FrameVel &out) const;
296 
307  bool getJointLimits(const std::string &end_effector_link,
308  KDL::JntArray &q_min, KDL::JntArray &q_max,
309  KDL::JntArray &q_vel_lim) const;
310 
319  bool getJointPositions(const std::string &end_effector_link,
320  const sensor_msgs::JointState &state,
321  KDL::JntArray &q) const;
322  bool getJointPositions(const std::string &end_effector_link,
323  const sensor_msgs::JointState &state,
324  Eigen::VectorXd &q) const;
325 
334  bool getJointVelocities(const std::string &end_effector_link,
335  const sensor_msgs::JointState &state,
336  KDL::JntArray &q_dot) const;
337 
346  bool getInertia(const std::string &end_effector_link,
347  const sensor_msgs::JointState &state, Eigen::MatrixXd &H);
348 
357  bool getGravity(const std::string &end_effector_link,
358  const sensor_msgs::JointState &state, Eigen::MatrixXd &g);
359 
368  bool getCoriolis(const std::string &end_effector_link,
369  const sensor_msgs::JointState &state,
370  Eigen::MatrixXd &coriolis);
371 
379  bool getNumJoints(const std::string &end_effector_link,
380  unsigned int &num_joints) const;
381 
382  private:
388 
389  typedef std::shared_ptr<IkSolverVel> IkSolverVelPtr;
390  typedef std::shared_ptr<IkSolverPos> IkSolverPosPtr;
391  typedef std::shared_ptr<FkSolverPos> FkSolverPosPtr;
392  typedef std::shared_ptr<FkSolverVel> FkSolverVelPtr;
393  typedef std::shared_ptr<JacSolver> JacSolverPtr;
394  typedef std::shared_ptr<KDL::ChainDynParam> ChainDynParamPtr;
395 
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_;
400  std::map<std::string, JacSolverPtr> jac_solver_;
401  std::map<std::string, KDL::Frame> eef_to_gripping_point_;
402  std::map<std::string, KDL::Frame> eef_to_sensor_point_;
403  std::map<std::string, KDL::Chain> chain_;
404  std::map<std::string, ChainDynParamPtr> dynamic_chain_;
405 
410  std::map<std::string, std::vector<std::string> >
415 
421  bool getParam();
422 
429  bool initializeArmCommon(const std::string &end_effector_link);
430 
439  bool getRigidTransform(const std::string &base_frame,
440  const std::string &target_frame,
441  KDL::Frame &out) const;
442 
455  bool getChainJointState(const sensor_msgs::JointState &current_state,
456  const std::string &end_effector_link,
457  KDL::JntArray &positions,
458  KDL::JntArrayVel &velocities) const;
459 
467  bool hasJoint(const KDL::Chain &chain, const std::string &joint_name) const;
468 };
469 
478 bool setKDLManager(const ArmInfo &arm_info,
479  std::shared_ptr<KDLManager> manager);
480 
489 bool setKDLManagerNso(const ArmInfo &arm_info,
490  std::shared_ptr<KDLManager> manager);
491 } // namespace generic_control_toolbox
492 #endif
bool getJointPositions(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q) const
bool getEefPose(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
bool initializeArm(const std::string &end_effector_link)
Definition: kdl_manager.cpp:96
bool getJointLimits(const std::string &end_effector_link, KDL::JntArray &q_min, KDL::JntArray &q_max, KDL::JntArray &q_vel_lim) const
const std::string WDLS_SOLVER("wdls")
bool getPoseIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Frame &in, KDL::JntArray &out) const
const std::string NSO_SOLVER("nso")
std::map< std::string, IkSolverPosPtr > ikpos_
KDL::ChainIkSolverVel IkSolverVel
std::map< std::string, FkSolverPosPtr > fkpos_
bool hasJoint(const KDL::Chain &chain, const std::string &joint_name) const
bool initializeArmCommon(const std::string &end_effector_link)
std::map< std::string, JacSolverPtr > jac_solver_
bool getSensorPoint(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
std::map< std::string, KDL::Chain > chain_
bool getChainJointState(const sensor_msgs::JointState &current_state, const std::string &end_effector_link, KDL::JntArray &positions, KDL::JntArrayVel &velocities) const
std::map< std::string, ChainDynParamPtr > dynamic_chain_
std::string chain_base_link_
list of actuated joints per arm
std::map< std::string, KDL::Frame > eef_to_sensor_point_
bool getNumJoints(const std::string &end_effector_link, unsigned int &num_joints) const
KDL::ChainFkSolverPos_recursive FkSolverPos
std::shared_ptr< IkSolverPos > IkSolverPosPtr
std::shared_ptr< FkSolverVel > FkSolverVelPtr
KDLManager(const std::string &chain_base_link, ros::NodeHandle nh=ros::NodeHandle("~"))
Definition: kdl_manager.cpp:5
bool getJointState(const std::string &end_effector_link, const Eigen::VectorXd &qdot, sensor_msgs::JointState &state) const
bool getRigidTransform(const std::string &base_frame, const std::string &target_frame, KDL::Frame &out) const
std::map< std::string, IkSolverVelPtr > ikvel_
bool getGrippingPoint(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const
bool getGrippingPoseIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Frame &in, KDL::JntArray &out) const
bool getEefTwist(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::FrameVel &out) const
std::shared_ptr< JacSolver > JacSolverPtr
KDL::ChainFkSolverVel_recursive FkSolverVel
bool setSensorPoint(const std::string &end_effector_link, const std::string &sensor_point_frame)
bool setKDLManagerNso(const ArmInfo &arm_info, std::shared_ptr< KDLManager > manager)
std::shared_ptr< KDL::ChainDynParam > ChainDynParamPtr
KDL::ChainJntToJacSolver JacSolver
bool getCoriolis(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &coriolis)
bool getInertia(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &H)
bool getGrippingTwist(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Twist &out) const
std::map< std::string, std::vector< std::string > > actuated_joint_names_
bool getJointVelocities(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q_dot) const
bool setKDLManager(const ArmInfo &arm_info, std::shared_ptr< KDLManager > manager)
bool setGrippingPoint(const std::string &end_effector_link, const std::string &gripping_point_frame)
bool getPoseFK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::JntArray &in, KDL::Frame &out) const
bool getJacobian(const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Jacobian &out) const
std::shared_ptr< FkSolverPos > FkSolverPosPtr
std::map< std::string, KDL::Frame > eef_to_gripping_point_
KDL::ChainIkSolverPos_LMA IkSolverPos
bool checkStateMessage(const std::string &end_effector_link, const sensor_msgs::JointState &state) const
std::map< std::string, FkSolverVelPtr > fkvel_
bool getVelIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const
std::shared_ptr< IkSolverVel > IkSolverVelPtr
bool getGravity(const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &g)
bool isInitialized(const std::string &end_effector_link) const
bool verifyPose(const std::string &end_effector_link, const KDL::Frame &in) const
bool getGrippingVelIK(const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44