00001 #ifndef __KDL_MANAGER__
00002 #define __KDL_MANAGER__
00003
00004 #include <eigen_conversions/eigen_kdl.h>
00005 #include <eigen_conversions/eigen_msg.h>
00006 #include <generic_control_toolbox/ArmInfo.h>
00007 #include <geometry_msgs/WrenchStamped.h>
00008 #include <kdl_conversions/kdl_msg.h>
00009 #include <ros/ros.h>
00010 #include <sensor_msgs/JointState.h>
00011 #include <tf/transform_listener.h>
00012 #include <urdf/model.h>
00013 #include <generic_control_toolbox/manager_base.hpp>
00014 #include <generic_control_toolbox/matrix_parser.hpp>
00015 #include <kdl/chaindynparam.hpp>
00016 #include <kdl/chainfksolverpos_recursive.hpp>
00017 #include <kdl/chainfksolvervel_recursive.hpp>
00018 #include <kdl/chainiksolverpos_lma.hpp>
00019 #include <kdl/chainiksolvervel_pinv_nso.hpp>
00020 #include <kdl/chainiksolvervel_wdls.hpp>
00021 #include <kdl/chainjnttojacsolver.hpp>
00022 #include <kdl/frames.hpp>
00023 #include <kdl/kdl.hpp>
00024 #include <kdl_parser/kdl_parser.hpp>
00025 #include <stdexcept>
00026
00027 const std::string WDLS_SOLVER("wdls"), NSO_SOLVER("nso");
00028
00029 namespace generic_control_toolbox
00030 {
00035 class KDLManager : public ManagerBase
00036 {
00037 public:
00038 KDLManager(const std::string &chain_base_link,
00039 ros::NodeHandle nh = ros::NodeHandle("~"));
00040 ~KDLManager();
00041
00050 bool initializeArm(const std::string &end_effector_link);
00051
00059 bool isInitialized(const std::string &end_effector_link) const;
00060
00071 bool checkStateMessage(const std::string &end_effector_link,
00072 const sensor_msgs::JointState &state) const;
00082 bool setGrippingPoint(const std::string &end_effector_link,
00083 const std::string &gripping_point_frame);
00084
00094 bool setSensorPoint(const std::string &end_effector_link,
00095 const std::string &sensor_point_frame);
00096
00106 bool getJointState(const std::string &end_effector_link,
00107 const Eigen::VectorXd &qdot,
00108 sensor_msgs::JointState &state) const;
00109
00120 bool getJointState(const std::string &end_effector_link,
00121 const Eigen::VectorXd &q, const Eigen::VectorXd &qdot,
00122 sensor_msgs::JointState &state) const;
00123
00136 bool getJointState(const std::string &end_effector_link,
00137 const Eigen::VectorXd &q, const Eigen::VectorXd &qdot,
00138 const Eigen::VectorXd &effort,
00139 sensor_msgs::JointState &state) const;
00140
00150 bool getGrippingPoint(const std::string &end_effector_link,
00151 const sensor_msgs::JointState &state,
00152 KDL::Frame &out) const;
00153
00163 bool getSensorPoint(const std::string &end_effector_link,
00164 const sensor_msgs::JointState &state,
00165 KDL::Frame &out) const;
00166
00176 bool getGrippingTwist(const std::string &end_effector_link,
00177 const sensor_msgs::JointState &state,
00178 KDL::Twist &out) const;
00179
00187 bool verifyPose(const std::string &end_effector_link,
00188 const KDL::Frame &in) const;
00189
00201 bool getPoseIK(const std::string &end_effector_link,
00202 const sensor_msgs::JointState &state, const KDL::Frame &in,
00203 KDL::JntArray &out) const;
00204
00216 bool getGrippingPoseIK(const std::string &end_effector_link,
00217 const sensor_msgs::JointState &state,
00218 const KDL::Frame &in, KDL::JntArray &out) const;
00219
00230 bool getPoseFK(const std::string &end_effector_link,
00231 const sensor_msgs::JointState &state, const KDL::JntArray &in,
00232 KDL::Frame &out) const;
00233
00244 bool getGrippingVelIK(const std::string &end_effector_link,
00245 const sensor_msgs::JointState &state,
00246 const KDL::Twist &in, KDL::JntArray &out) const;
00247
00258 bool getVelIK(const std::string &end_effector_link,
00259 const sensor_msgs::JointState &state, const KDL::Twist &in,
00260 KDL::JntArray &out) const;
00261
00270 bool getJacobian(const std::string &end_effector_link,
00271 const sensor_msgs::JointState &state,
00272 KDL::Jacobian &out) const;
00273
00282 bool getEefPose(const std::string &end_effector_link,
00283 const sensor_msgs::JointState &state, KDL::Frame &out) const;
00284
00293 bool getEefTwist(const std::string &end_effector_link,
00294 const sensor_msgs::JointState &state,
00295 KDL::FrameVel &out) const;
00296
00307 bool getJointLimits(const std::string &end_effector_link,
00308 KDL::JntArray &q_min, KDL::JntArray &q_max,
00309 KDL::JntArray &q_vel_lim) const;
00310
00319 bool getJointPositions(const std::string &end_effector_link,
00320 const sensor_msgs::JointState &state,
00321 KDL::JntArray &q) const;
00322 bool getJointPositions(const std::string &end_effector_link,
00323 const sensor_msgs::JointState &state,
00324 Eigen::VectorXd &q) const;
00325
00334 bool getJointVelocities(const std::string &end_effector_link,
00335 const sensor_msgs::JointState &state,
00336 KDL::JntArray &q_dot) const;
00337
00346 bool getInertia(const std::string &end_effector_link,
00347 const sensor_msgs::JointState &state, Eigen::MatrixXd &H);
00348
00357 bool getGravity(const std::string &end_effector_link,
00358 const sensor_msgs::JointState &state, Eigen::MatrixXd &g);
00359
00368 bool getCoriolis(const std::string &end_effector_link,
00369 const sensor_msgs::JointState &state,
00370 Eigen::MatrixXd &coriolis);
00371
00379 bool getNumJoints(const std::string &end_effector_link,
00380 unsigned int &num_joints) const;
00381
00382 private:
00383 typedef KDL::ChainIkSolverVel IkSolverVel;
00384 typedef KDL::ChainIkSolverPos_LMA IkSolverPos;
00385 typedef KDL::ChainFkSolverPos_recursive FkSolverPos;
00386 typedef KDL::ChainFkSolverVel_recursive FkSolverVel;
00387 typedef KDL::ChainJntToJacSolver JacSolver;
00388
00389 typedef std::shared_ptr<IkSolverVel> IkSolverVelPtr;
00390 typedef std::shared_ptr<IkSolverPos> IkSolverPosPtr;
00391 typedef std::shared_ptr<FkSolverPos> FkSolverPosPtr;
00392 typedef std::shared_ptr<FkSolverVel> FkSolverVelPtr;
00393 typedef std::shared_ptr<JacSolver> JacSolverPtr;
00394 typedef std::shared_ptr<KDL::ChainDynParam> ChainDynParamPtr;
00395
00396 std::map<std::string, IkSolverVelPtr> ikvel_;
00397 std::map<std::string, IkSolverPosPtr> ikpos_;
00398 std::map<std::string, FkSolverPosPtr> fkpos_;
00399 std::map<std::string, FkSolverVelPtr> fkvel_;
00400 std::map<std::string, JacSolverPtr> jac_solver_;
00401 std::map<std::string, KDL::Frame> eef_to_gripping_point_;
00402 std::map<std::string, KDL::Frame> eef_to_sensor_point_;
00403 std::map<std::string, KDL::Chain> chain_;
00404 std::map<std::string, ChainDynParamPtr> dynamic_chain_;
00405
00406 urdf::Model model_;
00407 ros::NodeHandle nh_;
00408 tf::TransformListener listener_;
00409 KDL::Vector gravity_in_chain_base_link_;
00410 std::map<std::string, std::vector<std::string> >
00411 actuated_joint_names_;
00412 std::string chain_base_link_, ikvel_solver_;
00413 double eps_, max_tf_attempts_, nso_weight_, ik_pos_tolerance_,
00414 ik_angle_tolerance_;
00415
00421 bool getParam();
00422
00429 bool initializeArmCommon(const std::string &end_effector_link);
00430
00439 bool getRigidTransform(const std::string &base_frame,
00440 const std::string &target_frame,
00441 KDL::Frame &out) const;
00442
00455 bool getChainJointState(const sensor_msgs::JointState ¤t_state,
00456 const std::string &end_effector_link,
00457 KDL::JntArray &positions,
00458 KDL::JntArrayVel &velocities) const;
00459
00467 bool hasJoint(const KDL::Chain &chain, const std::string &joint_name) const;
00468 };
00469
00478 bool setKDLManager(const ArmInfo &arm_info,
00479 std::shared_ptr<KDLManager> manager);
00480
00489 bool setKDLManagerNso(const ArmInfo &arm_info,
00490 std::shared_ptr<KDLManager> manager);
00491 }
00492 #endif