ros2_control - rolling
Public Member Functions | List of all members
kinematics_interface_kdl::KinematicsInterfaceKDL Class Reference
Inheritance diagram for kinematics_interface_kdl::KinematicsInterfaceKDL:
Inheritance graph
[legend]
Collaboration diagram for kinematics_interface_kdl::KinematicsInterfaceKDL:
Collaboration graph
[legend]

Public Member Functions

bool initialize (std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > parameters_interface, const std::string &end_effector_name) override
 Initialize plugin. This method must be called before any other.
 
bool convert_cartesian_deltas_to_joint_deltas (const Eigen::VectorXd &joint_pos, const Eigen::Matrix< double, 6, 1 > &delta_x, const std::string &link_name, Eigen::VectorXd &delta_theta) override
 Convert Cartesian delta-x to joint delta-theta, using the Jacobian. More...
 
bool convert_joint_deltas_to_cartesian_deltas (const Eigen::VectorXd &joint_pos, const Eigen::VectorXd &delta_theta, const std::string &link_name, Eigen::Matrix< double, 6, 1 > &delta_x) override
 Convert joint delta-theta to Cartesian delta-x. More...
 
bool calculate_link_transform (const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Isometry3d &transform) override
 Calculates the joint transform for a specified link using provided joint positions. More...
 
bool calculate_jacobian (const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix< double, 6, Eigen::Dynamic > &jacobian) override
 Calculates the jacobian for a specified link using provided joint positions. More...
 
- Public Member Functions inherited from kinematics_interface::KinematicsInterface
bool convert_cartesian_deltas_to_joint_deltas (std::vector< double > &joint_pos_vec, const std::vector< double > &delta_x_vec, const std::string &link_name, std::vector< double > &delta_theta_vec)
 
bool convert_joint_deltas_to_cartesian_deltas (const std::vector< double > &joint_pos_vec, const std::vector< double > &delta_theta_vec, const std::string &link_name, std::vector< double > &delta_x_vec)
 
bool calculate_link_transform (const std::vector< double > &joint_pos_vec, const std::string &link_name, Eigen::Isometry3d &transform)
 
bool calculate_jacobian (const std::vector< double > &joint_pos_vec, const std::string &link_name, Eigen::Matrix< double, 6, Eigen::Dynamic > &jacobian)
 

Member Function Documentation

◆ calculate_jacobian()

bool kinematics_interface_kdl::KinematicsInterfaceKDL::calculate_jacobian ( const Eigen::VectorXd &  joint_pos,
const std::string &  link_name,
Eigen::Matrix< double, 6, Eigen::Dynamic > &  jacobian 
)
overridevirtual

Calculates the jacobian for a specified link using provided joint positions.

Parameters
[in]joint_posjoint positions of the robot in radians
[in]link_namethe name of the link to find the transform for
[out]jacobianJacobian matrix of the specified link in column major format.
Returns
true if successful

Implements kinematics_interface::KinematicsInterface.

◆ calculate_link_transform()

bool kinematics_interface_kdl::KinematicsInterfaceKDL::calculate_link_transform ( const Eigen::VectorXd &  joint_pos,
const std::string &  link_name,
Eigen::Isometry3d &  transform 
)
overridevirtual

Calculates the joint transform for a specified link using provided joint positions.

Parameters
[in]joint_posjoint positions of the robot in radians
[in]link_namethe name of the link to find the transform for
[out]transformtransformation matrix of the specified link
Returns
true if successful

Implements kinematics_interface::KinematicsInterface.

◆ convert_cartesian_deltas_to_joint_deltas()

bool kinematics_interface_kdl::KinematicsInterfaceKDL::convert_cartesian_deltas_to_joint_deltas ( const Eigen::VectorXd &  joint_pos,
const Eigen::Matrix< double, 6, 1 > &  delta_x,
const std::string &  link_name,
Eigen::VectorXd &  delta_theta 
)
overridevirtual

Convert Cartesian delta-x to joint delta-theta, using the Jacobian.

Parameters
[in]joint_posjoint positions of the robot in radians
[in]delta_xinput Cartesian deltas (x, y, z, wx, wy, wz)
[in]link_namethe link name at which delta_x is applied
[out]delta_thetaoutputs joint deltas
Returns
true if successful

Implements kinematics_interface::KinematicsInterface.

◆ convert_joint_deltas_to_cartesian_deltas()

bool kinematics_interface_kdl::KinematicsInterfaceKDL::convert_joint_deltas_to_cartesian_deltas ( const Eigen::VectorXd &  joint_pos,
const Eigen::VectorXd &  delta_theta,
const std::string &  link_name,
Eigen::Matrix< double, 6, 1 > &  delta_x 
)
overridevirtual

Convert joint delta-theta to Cartesian delta-x.

Parameters
joint_posjoint positions of the robot in radians
[in]delta_thetajoint deltas
[in]link_namethe link name at which delta_x is calculated
[out]delta_xCartesian deltas (x, y, z, wx, wy, wz)
Returns
true if successful

Implements kinematics_interface::KinematicsInterface.


The documentation for this class was generated from the following files: