gripper_action_controller.h
Go to the documentation of this file.
1 // Copyright (C) 2014, SRI International
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of SRI International nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #ifndef GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_H
31 #define GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_H
32 
33 // C++ standard
34 #include <cassert>
35 #include <iterator>
36 #include <stdexcept>
37 #include <string>
38 
39 // Boost
40 #include <boost/shared_ptr.hpp>
41 #include <boost/scoped_ptr.hpp>
42 
43 // ROS
44 #include <ros/node_handle.h>
45 
46 // URDF
47 #include <urdf/model.h>
48 
49 // ROS messages
50 #include <control_msgs/GripperCommandAction.h>
51 
52 // actionlib
54 
55 // ros_controls
61 
62 // Project
64 
66 {
67 
74 template <class HardwareInterface>
76 {
77 public:
78 
82  struct Commands
83  {
84  double position_; // Last commanded position
85  double max_effort_; // Max allowed effort
86  };
87 
89 
92  bool init(HardwareInterface* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
93  /*\}*/
94 
98  void starting(const ros::Time& time);
99 
101  void stopping(const ros::Time& time);
102 
103  void update(const ros::Time& time, const ros::Duration& period);
104  /*\}*/
105 
107  Commands command_struct_, command_struct_rt_; // pre-allocated memory that is re-used to set the realtime buffer
108 
109 private:
110 
116 
118 
120 
121  bool verbose_;
122  std::string name_;
124  std::string joint_name_;
125 
126  HwIfaceAdapter hw_iface_adapter_;
127 
128  RealtimeGoalHandlePtr rt_active_goal_;
129  control_msgs::GripperCommandResultPtr pre_alloc_result_;
130 
132 
133  // ROS API
135  ActionServerPtr action_server_;
136 
138 
139  void goalCB(GoalHandle gh);
140  void cancelCB(GoalHandle gh);
141  void preemptActiveGoal();
142  void setHoldPosition(const ros::Time& time);
143 
146 
153  void checkForSuccess(const ros::Time& time, double error_position, double current_position, double current_velocity);
154 
155 };
156 
157 } // namespace
158 
160 
161 #endif // header guard
realtime_tools::RealtimeBuffer< Commands > command_
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
boost::shared_ptr< RealtimeGoalHandle > RealtimeGoalHandlePtr
HwIfaceAdapter hw_iface_adapter_
Adapts desired goal state to HW interface.
bool verbose_
Hard coded verbose flag to help in debugging.
void checkForSuccess(const ros::Time &time, double error_position, double current_position, double current_velocity)
Check for success and publish appropriate result and feedback.
void starting(const ros::Time &time)
Holds the current position.
RealtimeGoalHandlePtr rt_active_goal_
Currently active action goal, if any.
actionlib::ActionServer< control_msgs::GripperCommandAction > ActionServer
hardware_interface::JointHandle joint_
Handles to controlled joints.
void update(const ros::Time &time, const ros::Duration &period)
Helper class to simplify integrating the GripperActionController with different hardware interfaces...
realtime_tools::RealtimeServerGoalHandle< control_msgs::GripperCommandAction > RealtimeGoalHandle
void stopping(const ros::Time &time)
Cancels the active action goal, if any.
Store position and max effort in struct to allow easier realtime buffer usage.
HardwareInterfaceAdapter< HardwareInterface > HwIfaceAdapter
Controller for executing a gripper command action for simple single-dof grippers. ...
control_msgs::GripperCommandResultPtr pre_alloc_result_


gripper_action_controller
Author(s): Sachin Chitta
autogenerated on Thu Apr 11 2019 03:08:30