Public Member Functions | Public Attributes | Private Attributes
CobTwistController Class Reference

#include <cob_twist_controller.h>

List of all members.

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.
void twistCallback (const geometry_msgs::Twist::ConstPtr &msg)
 Orientation of twist_msg is with respect to chain_base coordinate system.
void twistStampedCallback (const geometry_msgs::TwistStamped::ConstPtr &msg)
 Orientation of twist_stamped_msg is with respect to coordinate system given in header.frame_id.
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_

Private Attributes

CallbackDataMediator callback_data_mediator_
KDL::Chain chain_
boost::shared_ptr
< cob_twist_controller::ControllerInterfaceBase
controller_interface_
boost::shared_ptr
< pluginlib::ClassLoader
< cob_twist_controller::ControllerInterfaceBase > > 
interface_loader_
boost::shared_ptr
< KDL::ChainFkSolverVel_recursive
jntToCartSolver_vel_
JointStates joint_states_
ros::Subscriber jointstate_sub_
ros::NodeHandle nh_
ros::Subscriber obstacle_distance_sub_
ros::Subscriber odometry_sub_
boost::shared_ptr
< InverseDifferentialKinematicsSolver
p_inv_diff_kin_solver_
ros::ServiceClient register_link_client_
tf::TransformListener tf_listener_
TwistControllerParams twist_controller_params_
ros::Publisher twist_direction_pub_
KDL::Twist twist_odometry_cb_
ros::Subscriber twist_stamped_sub_
ros::Subscriber twist_sub_

Detailed Description

Definition at line 51 of file cob_twist_controller.h.


Constructor & Destructor Documentation

Definition at line 84 of file cob_twist_controller.h.

Definition at line 88 of file cob_twist_controller.h.


Member Function Documentation

void CobTwistController::checkSolverAndConstraints ( cob_twist_controller::TwistControllerConfig &  config)

Definition at line 293 of file cob_twist_controller.cpp.

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 560 of file cob_twist_controller.cpp.

void CobTwistController::odometryCallback ( const nav_msgs::Odometry::ConstPtr &  msg)

Definition at line 589 of file cob_twist_controller.cpp.

void CobTwistController::reconfigureCallback ( cob_twist_controller::TwistControllerConfig &  config,
uint32_t  level 
)

Definition at line 228 of file cob_twist_controller.cpp.

Definition at line 198 of file cob_twist_controller.cpp.

Orientation of twist is with respect to chain_base coordinate system.

Definition at line 440 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 432 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 409 of file cob_twist_controller.cpp.

calculate rotation between twist-axis and z-axis of cylinder

Definition at line 471 of file cob_twist_controller.cpp.


Member Data Documentation

Definition at line 79 of file cob_twist_controller.h.

Definition at line 68 of file cob_twist_controller.h.

Definition at line 76 of file cob_twist_controller.h.

Definition at line 77 of file cob_twist_controller.h.

Definition at line 74 of file cob_twist_controller.h.

Definition at line 69 of file cob_twist_controller.h.

Definition at line 56 of file cob_twist_controller.h.

Definition at line 54 of file cob_twist_controller.h.

Definition at line 66 of file cob_twist_controller.h.

Definition at line 61 of file cob_twist_controller.h.

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.

Definition at line 65 of file cob_twist_controller.h.

Definition at line 81 of file cob_twist_controller.h.

Definition at line 72 of file cob_twist_controller.h.

Definition at line 63 of file cob_twist_controller.h.

Definition at line 70 of file cob_twist_controller.h.

Definition at line 59 of file cob_twist_controller.h.

Definition at line 58 of file cob_twist_controller.h.


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


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26