#include <cob_twist_controller.h>
Public Member Functions | |
void | checkSolverAndConstraints (cob_twist_controller::TwistControllerConfig &config) |
CobTwistController () | |
bool | initialize () |
void | jointstateCallback (const sensor_msgs::JointState::ConstPtr &msg) |
void | odometryCallback (const nav_msgs::Odometry::ConstPtr &msg) |
void | reconfigureCallback (cob_twist_controller::TwistControllerConfig &config, uint32_t level) |
bool | registerCollisionLinks () |
void | solveTwist (KDL::Twist twist) |
Orientation of twist is with respect to chain_base coordinate system. More... | |
void | twistCallback (const geometry_msgs::Twist::ConstPtr &msg) |
Orientation of twist_msg is with respect to chain_base coordinate system. More... | |
void | twistStampedCallback (const geometry_msgs::TwistStamped::ConstPtr &msg) |
Orientation of twist_stamped_msg is with respect to coordinate system given in header.frame_id. More... | |
void | visualizeTwist (KDL::Twist twist) |
~CobTwistController () | |
Public Attributes | |
boost::recursive_mutex | reconfig_mutex_ |
boost::shared_ptr< dynamic_reconfigure::Server< cob_twist_controller::TwistControllerConfig > > | reconfigure_server_ |
Definition at line 51 of file cob_twist_controller.h.
|
inline |
Definition at line 84 of file cob_twist_controller.h.
|
inline |
Definition at line 88 of file cob_twist_controller.h.
void CobTwistController::checkSolverAndConstraints | ( | cob_twist_controller::TwistControllerConfig & | config | ) |
Definition at line 251 of file cob_twist_controller.cpp.
bool CobTwistController::initialize | ( | ) |
parse robot_description and generate KDL chains
parse robot_description and set velocity limits
initialize configuration control solver
Setting up dynamic_reconfigure server for the TwistControlerConfig parameters
initialize variables and current joint values and velocities
give tf_listener some time to fill tf-cache
initialize ROS interfaces
publisher for visualizing current twist direction
Definition at line 33 of file cob_twist_controller.cpp.
void CobTwistController::jointstateCallback | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |
Definition at line 518 of file cob_twist_controller.cpp.
void CobTwistController::odometryCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Definition at line 547 of file cob_twist_controller.cpp.
void CobTwistController::reconfigureCallback | ( | cob_twist_controller::TwistControllerConfig & | config, |
uint32_t | level | ||
) |
Definition at line 235 of file cob_twist_controller.cpp.
bool CobTwistController::registerCollisionLinks | ( | ) |
Definition at line 205 of file cob_twist_controller.cpp.
void CobTwistController::solveTwist | ( | KDL::Twist | twist | ) |
Orientation of twist is with respect to chain_base coordinate system.
Definition at line 398 of file cob_twist_controller.cpp.
void CobTwistController::twistCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
Orientation of twist_msg is with respect to chain_base coordinate system.
Definition at line 390 of file cob_twist_controller.cpp.
void CobTwistController::twistStampedCallback | ( | const geometry_msgs::TwistStamped::ConstPtr & | msg | ) |
Orientation of twist_stamped_msg is with respect to coordinate system given in header.frame_id.
Definition at line 367 of file cob_twist_controller.cpp.
void CobTwistController::visualizeTwist | ( | KDL::Twist | twist | ) |
calculate rotation between twist-axis and z-axis of cylinder
Definition at line 429 of file cob_twist_controller.cpp.
|
private |
Definition at line 79 of file cob_twist_controller.h.
|
private |
Definition at line 68 of file cob_twist_controller.h.
|
private |
Definition at line 76 of file cob_twist_controller.h.
|
private |
Definition at line 77 of file cob_twist_controller.h.
|
private |
Definition at line 74 of file cob_twist_controller.h.
|
private |
Definition at line 69 of file cob_twist_controller.h.
|
private |
Definition at line 56 of file cob_twist_controller.h.
|
private |
Definition at line 54 of file cob_twist_controller.h.
|
private |
Definition at line 66 of file cob_twist_controller.h.
|
private |
Definition at line 61 of file cob_twist_controller.h.
|
private |
Definition at line 75 of file cob_twist_controller.h.
boost::recursive_mutex CobTwistController::reconfig_mutex_ |
Definition at line 111 of file cob_twist_controller.h.
boost::shared_ptr< dynamic_reconfigure::Server<cob_twist_controller::TwistControllerConfig> > CobTwistController::reconfigure_server_ |
Definition at line 112 of file cob_twist_controller.h.
|
private |
Definition at line 65 of file cob_twist_controller.h.
|
private |
Definition at line 81 of file cob_twist_controller.h.
|
private |
Definition at line 72 of file cob_twist_controller.h.
|
private |
Definition at line 63 of file cob_twist_controller.h.
|
private |
Definition at line 70 of file cob_twist_controller.h.
|
private |
Definition at line 59 of file cob_twist_controller.h.
|
private |
Definition at line 58 of file cob_twist_controller.h.