Go to the documentation of this file.
29 #include "twist_controller/TwistControllerConfig.h"
36 if (!n.
getParam(
"frame_id", frame_id))
43 server_.reset(
new dynamic_reconfigure::Server<twist_controller::TwistControllerConfig>(n));
46 handle_ = hw->getHandle(frame_id);
49 std::vector<std::string> joint_names;
50 if (!n.
getParam(
"joints", joint_names))
56 for (
auto& name : joint_names)
66 geometry_msgs::Twist twist;
78 geometry_msgs::Twist twist;
79 twist.linear.x =
gain_ * msg->linear.x;
80 twist.linear.y =
gain_ * msg->linear.y;
81 twist.linear.z =
gain_ * msg->linear.z;
82 twist.angular.x =
gain_ * msg->angular.x;
83 twist.angular.y =
gain_ * msg->angular.y;
84 twist.angular.z =
gain_ * msg->angular.z;
90 gain_ = config.twist_gain;
#define ROS_ERROR_STREAM(args)
virtual bool init(TwistCommandInterface *hw, ros::NodeHandle &n) override
bool getParam(const std::string &key, bool &b) const
void twistCallback(const geometry_msgs::TwistConstPtr &msg)
void reconfigureCallback(const twist_controller::TwistControllerConfig &config, uint32_t level)
TwistCommandHandle handle_
std::string resolveName(const std::string &name, bool remap=true) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::shared_ptr< dynamic_reconfigure::Server< twist_controller::TwistControllerConfig > > server_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
virtual void starting(const ros::Time &time) override
ros::Subscriber twist_sub_
A Cartesian ROS-controller for commanding target twists to a robot.
T param(const std::string ¶m_name, const T &default_val) const
realtime_tools::RealtimeBuffer< geometry_msgs::Twist > command_buffer_
twist_controller
Author(s): Felix Exner
, Stefan Scherzinger
autogenerated on Tue Oct 15 2024 02:09:17