Public Member Functions | Public Attributes | Private Attributes | List of all members
CobTwistController Class Reference

#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_
 

Private Attributes

CallbackDataMediator callback_data_mediator_
 
KDL::Chain chain_
 
boost::shared_ptr< cob_twist_controller::ControllerInterfaceBasecontroller_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< InverseDifferentialKinematicsSolverp_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

◆ CobTwistController()

CobTwistController::CobTwistController ( )
inline

Definition at line 84 of file cob_twist_controller.h.

◆ ~CobTwistController()

CobTwistController::~CobTwistController ( )
inline

Definition at line 88 of file cob_twist_controller.h.

Member Function Documentation

◆ checkSolverAndConstraints()

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

Definition at line 251 of file cob_twist_controller.cpp.

◆ initialize()

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.

◆ jointstateCallback()

void CobTwistController::jointstateCallback ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 518 of file cob_twist_controller.cpp.

◆ odometryCallback()

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

Definition at line 547 of file cob_twist_controller.cpp.

◆ reconfigureCallback()

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

Definition at line 235 of file cob_twist_controller.cpp.

◆ registerCollisionLinks()

bool CobTwistController::registerCollisionLinks ( )

Definition at line 205 of file cob_twist_controller.cpp.

◆ solveTwist()

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.

◆ twistCallback()

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.

◆ twistStampedCallback()

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.

◆ visualizeTwist()

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.

Member Data Documentation

◆ callback_data_mediator_

CallbackDataMediator CobTwistController::callback_data_mediator_
private

Definition at line 79 of file cob_twist_controller.h.

◆ chain_

KDL::Chain CobTwistController::chain_
private

Definition at line 68 of file cob_twist_controller.h.

◆ controller_interface_

boost::shared_ptr<cob_twist_controller::ControllerInterfaceBase> CobTwistController::controller_interface_
private

Definition at line 76 of file cob_twist_controller.h.

◆ interface_loader_

Definition at line 77 of file cob_twist_controller.h.

◆ jntToCartSolver_vel_

boost::shared_ptr<KDL::ChainFkSolverVel_recursive> CobTwistController::jntToCartSolver_vel_
private

Definition at line 74 of file cob_twist_controller.h.

◆ joint_states_

JointStates CobTwistController::joint_states_
private

Definition at line 69 of file cob_twist_controller.h.

◆ jointstate_sub_

ros::Subscriber CobTwistController::jointstate_sub_
private

Definition at line 56 of file cob_twist_controller.h.

◆ nh_

ros::NodeHandle CobTwistController::nh_
private

Definition at line 54 of file cob_twist_controller.h.

◆ obstacle_distance_sub_

ros::Subscriber CobTwistController::obstacle_distance_sub_
private

Definition at line 66 of file cob_twist_controller.h.

◆ odometry_sub_

ros::Subscriber CobTwistController::odometry_sub_
private

Definition at line 61 of file cob_twist_controller.h.

◆ p_inv_diff_kin_solver_

boost::shared_ptr<InverseDifferentialKinematicsSolver> CobTwistController::p_inv_diff_kin_solver_
private

Definition at line 75 of file cob_twist_controller.h.

◆ reconfig_mutex_

boost::recursive_mutex CobTwistController::reconfig_mutex_

Definition at line 111 of file cob_twist_controller.h.

◆ reconfigure_server_

boost::shared_ptr< dynamic_reconfigure::Server<cob_twist_controller::TwistControllerConfig> > CobTwistController::reconfigure_server_

Definition at line 112 of file cob_twist_controller.h.

◆ register_link_client_

ros::ServiceClient CobTwistController::register_link_client_
private

Definition at line 65 of file cob_twist_controller.h.

◆ tf_listener_

tf::TransformListener CobTwistController::tf_listener_
private

Definition at line 81 of file cob_twist_controller.h.

◆ twist_controller_params_

TwistControllerParams CobTwistController::twist_controller_params_
private

Definition at line 72 of file cob_twist_controller.h.

◆ twist_direction_pub_

ros::Publisher CobTwistController::twist_direction_pub_
private

Definition at line 63 of file cob_twist_controller.h.

◆ twist_odometry_cb_

KDL::Twist CobTwistController::twist_odometry_cb_
private

Definition at line 70 of file cob_twist_controller.h.

◆ twist_stamped_sub_

ros::Subscriber CobTwistController::twist_stamped_sub_
private

Definition at line 59 of file cob_twist_controller.h.

◆ twist_sub_

ros::Subscriber CobTwistController::twist_sub_
private

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 Mon May 1 2023 02:44:43