Abstract Helper Class to be used for Cartesian KinematicExtensions based on URDF. More...
#include <kinematic_extension_urdf.h>
Public Member Functions | |
virtual KDL::Jacobian | adjustJacobian (const KDL::Jacobian &jac_chain) |
virtual JointStates | adjustJointStates (const JointStates &joint_states) |
virtual LimiterParams | adjustLimiterParams (const LimiterParams &limiter_params) |
bool | initExtension () |
void | jointstateCallback (const sensor_msgs::JointState::ConstPtr &msg) |
KinematicExtensionURDF (const TwistControllerParams ¶ms) | |
virtual void | processResultExtension (const KDL::JntArray &q_dot_ik) |
~KinematicExtensionURDF () | |
Protected Attributes | |
KDL::Chain | chain_ |
ros::Publisher | command_pub_ |
std::string | ext_base_ |
unsigned int | ext_dof_ |
std::string | ext_tip_ |
std::vector< std::string > | joint_names_ |
ros::Subscriber | joint_state_sub_ |
JointStates | joint_states_ |
std::vector< double > | limits_acc_ |
std::vector< double > | limits_max_ |
std::vector< double > | limits_min_ |
std::vector< double > | limits_vel_ |
Abstract Helper Class to be used for Cartesian KinematicExtensions based on URDF.
Definition at line 35 of file kinematic_extension_urdf.h.
KinematicExtensionURDF::KinematicExtensionURDF | ( | const TwistControllerParams & | params | ) | [inline, explicit] |
Definition at line 38 of file kinematic_extension_urdf.h.
KinematicExtensionURDF::~KinematicExtensionURDF | ( | ) | [inline] |
Definition at line 42 of file kinematic_extension_urdf.h.
KDL::Jacobian KinematicExtensionURDF::adjustJacobian | ( | const KDL::Jacobian & | jac_chain | ) | [virtual] |
compose jac_full considering kinematical extension
get required transformations
angular velocities
linear velocities
explicit form of jacobian
Implements KinematicExtensionBase.
Definition at line 77 of file kinematic_extension_urdf.cpp.
JointStates KinematicExtensionURDF::adjustJointStates | ( | const JointStates & | joint_states | ) | [virtual] |
Implements KinematicExtensionBase.
Definition at line 182 of file kinematic_extension_urdf.cpp.
LimiterParams KinematicExtensionURDF::adjustLimiterParams | ( | const LimiterParams & | limiter_params | ) | [virtual] |
Implements KinematicExtensionBase.
Definition at line 209 of file kinematic_extension_urdf.cpp.
bool KinematicExtensionURDF::initExtension | ( | ) | [virtual] |
parse robot_description and generate KDL chains
parse robot_description and set velocity limits
Implements KinematicExtensionBase.
Definition at line 24 of file kinematic_extension_urdf.cpp.
void KinematicExtensionURDF::jointstateCallback | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |
Definition at line 234 of file kinematic_extension_urdf.cpp.
void KinematicExtensionURDF::processResultExtension | ( | const KDL::JntArray & | q_dot_ik | ) | [virtual] |
Implements KinematicExtensionBase.
Definition at line 222 of file kinematic_extension_urdf.cpp.
KDL::Chain KinematicExtensionURDF::chain_ [protected] |
Definition at line 58 of file kinematic_extension_urdf.h.
ros::Publisher KinematicExtensionURDF::command_pub_ [protected] |
Definition at line 53 of file kinematic_extension_urdf.h.
std::string KinematicExtensionURDF::ext_base_ [protected] |
Definition at line 56 of file kinematic_extension_urdf.h.
unsigned int KinematicExtensionURDF::ext_dof_ [protected] |
Definition at line 59 of file kinematic_extension_urdf.h.
std::string KinematicExtensionURDF::ext_tip_ [protected] |
Definition at line 57 of file kinematic_extension_urdf.h.
std::vector<std::string> KinematicExtensionURDF::joint_names_ [protected] |
Definition at line 60 of file kinematic_extension_urdf.h.
Definition at line 54 of file kinematic_extension_urdf.h.
JointStates KinematicExtensionURDF::joint_states_ [protected] |
Definition at line 61 of file kinematic_extension_urdf.h.
std::vector<double> KinematicExtensionURDF::limits_acc_ [protected] |
Definition at line 65 of file kinematic_extension_urdf.h.
std::vector<double> KinematicExtensionURDF::limits_max_ [protected] |
Definition at line 62 of file kinematic_extension_urdf.h.
std::vector<double> KinematicExtensionURDF::limits_min_ [protected] |
Definition at line 63 of file kinematic_extension_urdf.h.
std::vector<double> KinematicExtensionURDF::limits_vel_ [protected] |
Definition at line 64 of file kinematic_extension_urdf.h.