#include <kdl_manager.hpp>
Public Member Functions | |
bool | checkStateMessage (const std::string &end_effector_link, const sensor_msgs::JointState &state) const |
bool | getCoriolis (const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &coriolis) |
bool | getEefPose (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const |
bool | getEefTwist (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::FrameVel &out) const |
bool | getGravity (const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &g) |
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 | getGrippingTwist (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Twist &out) const |
bool | getGrippingVelIK (const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const |
bool | getInertia (const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::MatrixXd &H) |
bool | getJacobian (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Jacobian &out) const |
bool | getJointLimits (const std::string &end_effector_link, KDL::JntArray &q_min, KDL::JntArray &q_max, KDL::JntArray &q_vel_lim) const |
bool | getJointPositions (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q) const |
bool | getJointPositions (const std::string &end_effector_link, const sensor_msgs::JointState &state, Eigen::VectorXd &q) const |
bool | getJointState (const std::string &end_effector_link, const Eigen::VectorXd &qdot, sensor_msgs::JointState &state) const |
bool | getJointState (const std::string &end_effector_link, const Eigen::VectorXd &q, const Eigen::VectorXd &qdot, sensor_msgs::JointState &state) const |
bool | getJointState (const std::string &end_effector_link, const Eigen::VectorXd &q, const Eigen::VectorXd &qdot, const Eigen::VectorXd &effort, sensor_msgs::JointState &state) const |
bool | getJointVelocities (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::JntArray &q_dot) const |
bool | getNumJoints (const std::string &end_effector_link, unsigned int &num_joints) const |
bool | getPoseFK (const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::JntArray &in, KDL::Frame &out) const |
bool | getPoseIK (const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Frame &in, KDL::JntArray &out) const |
bool | getSensorPoint (const std::string &end_effector_link, const sensor_msgs::JointState &state, KDL::Frame &out) const |
bool | getVelIK (const std::string &end_effector_link, const sensor_msgs::JointState &state, const KDL::Twist &in, KDL::JntArray &out) const |
bool | initializeArm (const std::string &end_effector_link) |
bool | isInitialized (const std::string &end_effector_link) const |
KDLManager (const std::string &chain_base_link, ros::NodeHandle nh=ros::NodeHandle("~")) | |
bool | setGrippingPoint (const std::string &end_effector_link, const std::string &gripping_point_frame) |
bool | setSensorPoint (const std::string &end_effector_link, const std::string &sensor_point_frame) |
bool | verifyPose (const std::string &end_effector_link, const KDL::Frame &in) const |
~KDLManager () | |
Public Member Functions inherited from generic_control_toolbox::ManagerBase | |
ManagerBase () | |
virtual | ~ManagerBase () |
Private Types | |
typedef std::shared_ptr< KDL::ChainDynParam > | ChainDynParamPtr |
typedef KDL::ChainFkSolverPos_recursive | FkSolverPos |
typedef std::shared_ptr< FkSolverPos > | FkSolverPosPtr |
typedef KDL::ChainFkSolverVel_recursive | FkSolverVel |
typedef std::shared_ptr< FkSolverVel > | FkSolverVelPtr |
typedef KDL::ChainIkSolverPos_LMA | IkSolverPos |
typedef std::shared_ptr< IkSolverPos > | IkSolverPosPtr |
typedef KDL::ChainIkSolverVel | IkSolverVel |
typedef std::shared_ptr< IkSolverVel > | IkSolverVelPtr |
typedef KDL::ChainJntToJacSolver | JacSolver |
typedef std::shared_ptr< JacSolver > | JacSolverPtr |
Private Member Functions | |
bool | getChainJointState (const sensor_msgs::JointState ¤t_state, const std::string &end_effector_link, KDL::JntArray &positions, KDL::JntArrayVel &velocities) const |
bool | getParam () |
bool | getRigidTransform (const std::string &base_frame, const std::string &target_frame, KDL::Frame &out) const |
bool | hasJoint (const KDL::Chain &chain, const std::string &joint_name) const |
bool | initializeArmCommon (const std::string &end_effector_link) |
Private Attributes | |
std::map< std::string, std::vector< std::string > > | actuated_joint_names_ |
std::map< std::string, KDL::Chain > | chain_ |
std::string | chain_base_link_ |
list of actuated joints per arm More... | |
std::map< std::string, ChainDynParamPtr > | dynamic_chain_ |
std::map< std::string, KDL::Frame > | eef_to_gripping_point_ |
std::map< std::string, KDL::Frame > | eef_to_sensor_point_ |
double | eps_ |
std::map< std::string, FkSolverPosPtr > | fkpos_ |
std::map< std::string, FkSolverVelPtr > | fkvel_ |
KDL::Vector | gravity_in_chain_base_link_ |
double | ik_angle_tolerance_ |
double | ik_pos_tolerance_ |
std::map< std::string, IkSolverPosPtr > | ikpos_ |
std::map< std::string, IkSolverVelPtr > | ikvel_ |
std::string | ikvel_solver_ |
std::map< std::string, JacSolverPtr > | jac_solver_ |
tf::TransformListener | listener_ |
double | max_tf_attempts_ |
urdf::Model | model_ |
ros::NodeHandle | nh_ |
double | nso_weight_ |
Loads and maintains a URDF robot description and provides access to relevant KDL objects/solvers. Supports n end-effectors
Definition at line 35 of file kdl_manager.hpp.
|
private |
Definition at line 394 of file kdl_manager.hpp.
Definition at line 385 of file kdl_manager.hpp.
|
private |
Definition at line 391 of file kdl_manager.hpp.
Definition at line 386 of file kdl_manager.hpp.
|
private |
Definition at line 392 of file kdl_manager.hpp.
Definition at line 384 of file kdl_manager.hpp.
|
private |
Definition at line 390 of file kdl_manager.hpp.
Definition at line 383 of file kdl_manager.hpp.
|
private |
Definition at line 389 of file kdl_manager.hpp.
Definition at line 387 of file kdl_manager.hpp.
|
private |
Definition at line 393 of file kdl_manager.hpp.
generic_control_toolbox::KDLManager::KDLManager | ( | const std::string & | chain_base_link, |
ros::NodeHandle | nh = ros::NodeHandle("~") |
||
) |
Definition at line 5 of file kdl_manager.cpp.
generic_control_toolbox::KDLManager::~KDLManager | ( | ) |
Definition at line 17 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::checkStateMessage | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state | ||
) | const |
Checks if the provided joint state message has the required information for the kinematic chain indexed by the given end effector link. Useful with the joint states topic does not contain consistently the same information.
end_effector_link | The end_effector link name. |
state | The joint state message to verify. |
Definition at line 934 of file kdl_manager.cpp.
|
private |
Fills in the joint arrays with the state of a given kinematic chain. The joint state might include joints outside of the kinematic chain, so there is the need to process it.
current_state | The robot joint state. |
arm | The target arm index. |
positions | The joint positions of the kinematic chain. |
velocities | The joint velocities of the kinematic chain. |
Definition at line 976 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getCoriolis | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
Eigen::MatrixXd & | coriolis | ||
) |
Computes the coriolis forces exerted in the given chain.
end_effector_link | The name of the requested end-effector. |
state | The current joint state. |
coriolis | The output coriolis effort. |
Definition at line 675 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getEefPose | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::Frame & | out | ||
) | const |
Returns the pose of the requested end-effector, given a joint state.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
out | The resulting eef pose. |
Definition at line 489 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getEefTwist | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::FrameVel & | out | ||
) | const |
Returns the twist of the requested end-effector, given a joint state.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
out | The resulting eef twist. |
Definition at line 510 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getGravity | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
Eigen::MatrixXd & | g | ||
) |
Computes the predicted gravity effect on the given chain.
end_effector_link | The name of the requested end-effector. |
state | The current joint state. |
g | The output gravity effort. |
Definition at line 651 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getGrippingPoint | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::Frame & | out | ||
) | const |
Returns the gripping point of the chosen arm. By default this is set to be the end-effector pose.
end_effector_link | The arm's end-effector name. |
state | The robot joint state. |
out | The resulting gripping point frame. |
Definition at line 408 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getGrippingPoseIK | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
const KDL::Frame & | in, | ||
KDL::JntArray & | out | ||
) | const |
Returns the inverse kinematics of a chain gripping point , given a desired pose.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
in | Desired eef pose. |
out | Joint state for the desired gripping pose. |
Definition at line 818 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getGrippingTwist | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::Twist & | out | ||
) | const |
Returns the twist of the requested end-effector's gripping point. By default this is set to be the end-effector's twist.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
out | The resulting eef twist. |
Definition at line 446 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getGrippingVelIK | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
const KDL::Twist & | in, | ||
KDL::JntArray & | out | ||
) | const |
Returns the inverse differential kinematics of the requested gripping point, given a desired twist.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
in | Desired gripping point twist, in the gripping point frame. |
out | Joint state for the desired twist. |
Definition at line 847 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getInertia | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
Eigen::MatrixXd & | H | ||
) |
Computes the inertia matrix of the kinematic chain.
end_effector_link | The name of the requested end-effector. |
state | The current joint state. |
H | The output inertia matrix. |
Definition at line 634 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJacobian | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::Jacobian & | out | ||
) | const |
Returns the jacobian the requested end-effector's chain.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
out | End-effector's jacobian. |
Definition at line 913 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointLimits | ( | const std::string & | end_effector_link, |
KDL::JntArray & | q_min, | ||
KDL::JntArray & | q_max, | ||
KDL::JntArray & | q_vel_lim | ||
) | const |
Returns the joint limits for all the actuated joints in the eef kinematic chain.
end_effector_link | The name of the requested end-effector. |
q_min | The lower joint position limit. |
q_max | The upper joint position limit. |
q_vel_lim | The maximum joint velocity. |
Definition at line 530 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointPositions | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::JntArray & | q | ||
) | const |
Returns the current joint positions in the KDL format.
end_effector_link | The name of the requested end-effector. |
state | The current joint state |
q | The joint positions in KDL format |
Definition at line 574 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointPositions | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
Eigen::VectorXd & | q | ||
) | const |
Definition at line 593 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointState | ( | const std::string & | end_effector_link, |
const Eigen::VectorXd & | qdot, | ||
sensor_msgs::JointState & | state | ||
) | const |
Fills the joint state message given only joint velocities. Joint positions are taken from the joint state message.
end_effector_link | The chain's end_effector. |
qdot | The chain's joint velocities. |
state | The generated joint state message. |
Definition at line 256 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointState | ( | const std::string & | end_effector_link, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | qdot, | ||
sensor_msgs::JointState & | state | ||
) | const |
Fills the joint state message appropriately given the joint positions and velocities of the selected end-effector's joint chain.
end_effector_link | The chain's end_effector. |
q | The chain's joint posisitions. |
qdot | The chain's joint velocities. |
state | The generated joint state message. |
Definition at line 301 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointState | ( | const std::string & | end_effector_link, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | qdot, | ||
const Eigen::VectorXd & | effort, | ||
sensor_msgs::JointState & | state | ||
) | const |
Fills the joint state message appropriately given the joint positions, velocities and efforts of the selected end-effector's joint chain.
end_effector_link | The chain's end_effector. |
q | The chain's joint posisitions. |
qdot | The chain's joint velocities. |
effort | The chain's joint efforts. |
state | The generated joint state message. |
Definition at line 357 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getJointVelocities | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::JntArray & | q_dot | ||
) | const |
Returns the current joint velocities in the KDL format.
end_effector_link | The name of the requested end-effector. |
state | The current joint state. |
q_dot | The joint velocities in the KDL format. |
Definition at line 613 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getNumJoints | ( | const std::string & | end_effector_link, |
unsigned int & | num_joints | ||
) | const |
Returns the number of joints for a given chain.
end_effector_link | The name of the requested end-effector. |
num_joints | The number of joints of the associated kinematic chain. |
Definition at line 1036 of file kdl_manager.cpp.
|
private |
Loads the manager parameters
Definition at line 19 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getPoseFK | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
const KDL::JntArray & | in, | ||
KDL::Frame & | out | ||
) | const |
Returns the forward kinematics of the requested end-effector, given a desired joint state.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
in | Desired eef joint state. |
out | Pose for the desired joint state. |
Definition at line 834 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getPoseIK | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
const KDL::Frame & | in, | ||
KDL::JntArray & | out | ||
) | const |
Returns the inverse kinematics of the requested end-effector, given a desired pose.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
in | Desired eef pose. |
out | Joint state for the desired pose. |
Definition at line 767 of file kdl_manager.cpp.
|
private |
Queries TF to get the rigid transform between two frames
base_frame | The base frame of the transform. |
target_frame | The target frame of the transform. |
out | The rigid transform between the two frames in the KDL format. |
Definition at line 697 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getSensorPoint | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
KDL::Frame & | out | ||
) | const |
Returns the sensor point of the chosen arm. By default this is set to be the end-effector pose.
end_effector_link | The arm's end-effector name. |
state | The robot joint state. |
out | The resulting sensor point frame. |
Definition at line 427 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::getVelIK | ( | const std::string & | end_effector_link, |
const sensor_msgs::JointState & | state, | ||
const KDL::Twist & | in, | ||
KDL::JntArray & | out | ||
) | const |
Returns the inverse differential kinematics of the requested end-effector, given a desired twist.
end_effector_link | The name of the requested end-effector. |
state | The current robot joint state. |
in | Desired eef twist. |
out | Joint state for the desired twist. |
Definition at line 892 of file kdl_manager.cpp.
|
private |
Check if a chain has the given joint_name.
chain | The kinematic chain where to look for the joint. |
joint_name | The joint name we wish to check. |
Definition at line 1022 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::initializeArm | ( | const std::string & | end_effector_link | ) |
Initialize the kinematic chain, solvers and joint arrays for an arm defined by its end-effector link. The kinematic chain is assumed to start at chain_base_link_.
end_effector_link | The final link of the kinematic chain. |
Definition at line 96 of file kdl_manager.cpp.
|
private |
Common part of the initialize arm methods.
end_effector_link | The name of the requested end-effector. |
Definition at line 152 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::isInitialized | ( | const std::string & | end_effector_link | ) | const |
Checks whether a kinematic chain with the given end-effector link was initialized in a KDL manager instance.
end_effector_link | The final link of the kinematic chain. |
Definition at line 147 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::setGrippingPoint | ( | const std::string & | end_effector_link, |
const std::string & | gripping_point_frame | ||
) |
Queries TF for the rigid transform between the end-effector link frame and the gripping point frame and stores it as a KDL Frame.
end_effector_link | The end-effector link name. |
gripping_point_frame | TF name of the gripping point frame. |
Definition at line 215 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::setSensorPoint | ( | const std::string & | end_effector_link, |
const std::string & | sensor_point_frame | ||
) |
Queries TF for the rigid transform between the end-effector link frame and a sensor point frame, and stores it as a KDL Frame.
end_effector_link | The end-effector link name. |
sensor_point_frame | TF name of the sensor point frame. |
Definition at line 236 of file kdl_manager.cpp.
bool generic_control_toolbox::KDLManager::verifyPose | ( | const std::string & | end_effector_link, |
const KDL::Frame & | in | ||
) | const |
Verifies if a given pose is reachable by the requested end-effector.
end_effector_link | The name of the requested end-effector. |
in | The pose that is to be verified. |
Definition at line 739 of file kdl_manager.cpp.
|
private |
Definition at line 411 of file kdl_manager.hpp.
|
private |
Definition at line 403 of file kdl_manager.hpp.
|
private |
list of actuated joints per arm
Definition at line 412 of file kdl_manager.hpp.
|
private |
Definition at line 404 of file kdl_manager.hpp.
|
private |
Definition at line 401 of file kdl_manager.hpp.
|
private |
Definition at line 402 of file kdl_manager.hpp.
|
private |
Definition at line 413 of file kdl_manager.hpp.
|
private |
Definition at line 398 of file kdl_manager.hpp.
|
private |
Definition at line 399 of file kdl_manager.hpp.
|
private |
Definition at line 409 of file kdl_manager.hpp.
|
private |
Definition at line 413 of file kdl_manager.hpp.
|
private |
Definition at line 413 of file kdl_manager.hpp.
|
private |
Definition at line 397 of file kdl_manager.hpp.
|
private |
Definition at line 396 of file kdl_manager.hpp.
|
private |
Definition at line 412 of file kdl_manager.hpp.
|
private |
Definition at line 400 of file kdl_manager.hpp.
|
private |
Definition at line 408 of file kdl_manager.hpp.
|
private |
Definition at line 413 of file kdl_manager.hpp.
|
private |
Definition at line 406 of file kdl_manager.hpp.
|
private |
Definition at line 407 of file kdl_manager.hpp.
|
private |
Definition at line 413 of file kdl_manager.hpp.