18 #ifndef COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H 19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H 24 #include <std_msgs/Float64MultiArray.h> 25 #include <sensor_msgs/JointState.h> 29 #include <Eigen/Geometry> 99 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
~KinematicExtensionURDF()
virtual JointStates adjustJointStates(const JointStates &joint_states)
std::vector< std::string > joint_names_
void jointstateCallback(const sensor_msgs::JointState::ConstPtr &msg)
Abstract Helper Class to be used for Cartesian KinematicExtensions based on URDF. ...
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
Base class for kinematic extensions.
std::vector< double > limits_min_
ros::Subscriber joint_state_sub_
const TwistControllerParams & params_
~KinematicExtensionTorso()
std::string chain_base_link
KinematicExtensionURDF(const TwistControllerParams ¶ms)
KinematicExtensionTorso(const TwistControllerParams ¶ms)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< double > limits_max_
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
std::vector< double > limits_acc_
std::vector< double > limits_vel_
JointStates joint_states_
Class implementing a KinematicExtension for Torso based on URDF.
ros::Publisher command_pub_