Go to the documentation of this file.
18 #ifndef COB_TWIST_CONTROLLER_COB_TWIST_CONTROLLER_H
19 #define COB_TWIST_CONTROLLER_COB_TWIST_CONTROLLER_H
23 #include <std_msgs/ColorRGBA.h>
24 #include <sensor_msgs/JointState.h>
25 #include <geometry_msgs/Twist.h>
26 #include <nav_msgs/Odometry.h>
31 #include <kdl/chainfksolvervel_recursive.hpp>
32 #include <kdl/jntarray.hpp>
33 #include <kdl/jntarrayvel.hpp>
34 #include <kdl/frames.hpp>
39 #include <boost/thread/mutex.hpp>
40 #include <boost/shared_ptr.hpp>
42 #include <dynamic_reconfigure/server.h>
45 #include <cob_twist_controller/TwistControllerConfig.h>
90 this->jntToCartSolver_vel_.reset();
91 this->p_inv_diff_kin_solver_.reset();
92 this->controller_interface_.reset();
100 void reconfigureCallback(cob_twist_controller::TwistControllerConfig& config, uint32_t level);
105 void twistCallback(
const geometry_msgs::Twist::ConstPtr& msg);
115 #endif // COB_TWIST_CONTROLLER_COB_TWIST_CONTROLLER_H
KDL::Twist twist_odometry_cb_
TwistControllerParams twist_controller_params_
boost::shared_ptr< pluginlib::ClassLoader< cob_twist_controller::ControllerInterfaceBase > > interface_loader_
void jointstateCallback(const sensor_msgs::JointState::ConstPtr &msg)
void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg)
boost::recursive_mutex reconfig_mutex_
ros::Publisher twist_direction_pub_
ros::ServiceClient register_link_client_
JointStates joint_states_
tf::TransformListener tf_listener_
void twistStampedCallback(const geometry_msgs::TwistStamped::ConstPtr &msg)
Orientation of twist_stamped_msg is with respect to coordinate system given in header....
bool registerCollisionLinks()
boost::shared_ptr< InverseDifferentialKinematicsSolver > p_inv_diff_kin_solver_
void visualizeTwist(KDL::Twist twist)
ros::Subscriber twist_stamped_sub_
boost::shared_ptr< cob_twist_controller::ControllerInterfaceBase > controller_interface_
CallbackDataMediator callback_data_mediator_
ros::Subscriber twist_sub_
ros::Subscriber obstacle_distance_sub_
void checkSolverAndConstraints(cob_twist_controller::TwistControllerConfig &config)
boost::shared_ptr< KDL::ChainFkSolverVel_recursive > jntToCartSolver_vel_
ros::Subscriber odometry_sub_
boost::shared_ptr< dynamic_reconfigure::Server< cob_twist_controller::TwistControllerConfig > > reconfigure_server_
void reconfigureCallback(cob_twist_controller::TwistControllerConfig &config, uint32_t level)
void twistCallback(const geometry_msgs::Twist::ConstPtr &msg)
Orientation of twist_msg is with respect to chain_base coordinate system.
ros::Subscriber jointstate_sub_
void solveTwist(KDL::Twist twist)
Orientation of twist is with respect to chain_base coordinate system.
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43