forward_command_controller.h
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * Copyright (c) 2012, hiDOF, Inc.
7  * Copyright (c) 2013, PAL Robotics, S.L.
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the Willow Garage nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *********************************************************************/
37 
38 #ifndef FORWARD_COMMAND_CONTROLLER_FORWARD_COMMAND_CONTROLLER_H
39 #define FORWARD_COMMAND_CONTROLLER_FORWARD_COMMAND_CONTROLLER_H
40 
41 #include <ros/node_handle.h>
44 #include <std_msgs/Float64.h>
46 
47 
49 {
50 
68 template <class T>
70 {
71 public:
74 
75  bool init(T* hw, ros::NodeHandle &n)
76  {
77  std::string joint_name;
78  if (!n.getParam("joint", joint_name))
79  {
80  ROS_ERROR("No joint given (namespace: %s)", n.getNamespace().c_str());
81  return false;
82  }
83  joint_ = hw->getHandle(joint_name);
84  sub_command_ = n.subscribe<std_msgs::Float64>("command", 1, &ForwardCommandController::commandCB, this);
85  return true;
86  }
87 
88  void starting(const ros::Time& time);
89  void update(const ros::Time& /*time*/, const ros::Duration& /*period*/) {joint_.setCommand(*command_buffer_.readFromRT());}
90 
93 
94 private:
96  void commandCB(const std_msgs::Float64ConstPtr& msg) {command_buffer_.writeFromNonRT(msg->data);}
97 };
98 
99 }
100 
101 #endif
void commandCB(const std_msgs::Float64ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void writeFromNonRT(const T &data)
realtime_tools::RealtimeBuffer< double > command_buffer_
const std::string & getNamespace() const
void update(const ros::Time &, const ros::Duration &)
void setCommand(double command)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)


forward_command_controller
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Apr 18 2020 03:58:10