twist_controller.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //----------------------------------------------------------------------
25 //----------------------------------------------------------------------
26 
29 #include "twist_controller/TwistControllerConfig.h"
30 
32 {
34 {
35  std::string frame_id;
36  if (!n.getParam("frame_id", frame_id))
37  {
38  ROS_ERROR_STREAM("Required parameter " << n.resolveName("frame_id") << " not given");
39  return false;
40  }
41 
42  gain_ = n.param("twist_gain", 0.1);
43  server_.reset(new dynamic_reconfigure::Server<twist_controller::TwistControllerConfig>(n));
44  server_->setCallback(boost::bind(&TwistController::reconfigureCallback, this, _1, _2));
45 
46  handle_ = hw->getHandle(frame_id);
47  twist_sub_ = n.subscribe<geometry_msgs::Twist>("command", 1, &TwistController::twistCallback, this);
48 
49  std::vector<std::string> joint_names;
50  if (!n.getParam("joints", joint_names))
51  {
52  ROS_ERROR_STREAM("Failed to read required parameter '" << n.resolveName("joints") << ".");
53  return false;
54  }
55 
56  for (auto& name : joint_names)
57  {
58  hw->claim(name);
59  }
60 
61  return true;
62 }
63 
65 {
66  geometry_msgs::Twist twist;
67  twist.linear.x = 0;
68  twist.linear.y = 0;
69  twist.linear.z = 0;
70  twist.angular.x = 0;
71  twist.angular.y = 0;
72  twist.angular.z = 0;
74 }
75 
76 void TwistController::twistCallback(const geometry_msgs::TwistConstPtr& msg)
77 {
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;
86 }
87 
88 void TwistController ::reconfigureCallback(const twist_controller::TwistControllerConfig& config, uint32_t level)
89 {
90  gain_ = config.twist_gain;
91 }
92 } // namespace ros_controllers_cartesian
93 
realtime_tools::RealtimeBuffer::writeFromNonRT
void writeFromNonRT(const T &data)
ros_controllers_cartesian
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros_controllers_cartesian::TwistController::init
virtual bool init(TwistCommandInterface *hw, ros::NodeHandle &n) override
Definition: twist_controller.cpp:33
ros_controllers_cartesian::TwistCommandInterface
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros_controllers_cartesian::TwistController::twistCallback
void twistCallback(const geometry_msgs::TwistConstPtr &msg)
Definition: twist_controller.cpp:76
ros_controllers_cartesian::TwistController::reconfigureCallback
void reconfigureCallback(const twist_controller::TwistControllerConfig &config, uint32_t level)
Definition: twist_controller.cpp:88
ros_controllers_cartesian::TwistController::handle_
TwistCommandHandle handle_
Definition: twist_controller.h:63
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros_controllers_cartesian::TwistController::server_
std::shared_ptr< dynamic_reconfigure::Server< twist_controller::TwistControllerConfig > > server_
Definition: twist_controller.h:71
ros_controllers_cartesian::TwistController::gain_
double gain_
Definition: twist_controller.h:70
ros::NodeHandle::subscribe
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())
ros_controllers_cartesian::TwistController::starting
virtual void starting(const ros::Time &time) override
Definition: twist_controller.cpp:64
ros_controllers_cartesian::TwistController::twist_sub_
ros::Subscriber twist_sub_
Definition: twist_controller.h:67
twist_controller.h
ros::Time
class_list_macros.hpp
ros_controllers_cartesian::TwistController
A Cartesian ROS-controller for commanding target twists to a robot.
Definition: twist_controller.h:48
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros_controllers_cartesian::TwistController::command_buffer_
realtime_tools::RealtimeBuffer< geometry_msgs::Twist > command_buffer_
Definition: twist_controller.h:64
ros::NodeHandle


twist_controller
Author(s): Felix Exner , Stefan Scherzinger
autogenerated on Tue Oct 15 2024 02:09:17