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 #pragma once
31 
32 
33 // C++ standard
34 #include <cassert>
35 #include <stdexcept>
36 #include <string>
37 #include <memory>
38 
39 // ROS
40 #include <ros/node_handle.h>
41 
42 // URDF
43 #include <urdf/model.h>
44 
45 // ROS messages
46 #include <control_msgs/GripperCommandAction.h>
47 
48 // actionlib
50 
51 // ros_controls
57 
58 // Project
60 
62 {
63 
70 template <class HardwareInterface>
72 {
73 public:
74 
78  struct Commands
79  {
80  double position_; // Last commanded position
81  double max_effort_; // Max allowed effort
82  };
83 
85 
88  bool init(HardwareInterface* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
89  /*\}*/
90 
94  void starting(const ros::Time& time);
95 
97  void stopping(const ros::Time& time);
98 
99  void update(const ros::Time& time, const ros::Duration& period);
100  /*\}*/
101 
103  Commands command_struct_, command_struct_rt_; // pre-allocated memory that is re-used to set the realtime buffer
104 
105 private:
106 
108  typedef std::shared_ptr<ActionServer> ActionServerPtr;
112 
114 
116 
117  bool verbose_;
118  std::string name_;
120  std::string joint_name_;
121 
122  HwIfaceAdapter hw_iface_adapter_;
123 
124  RealtimeGoalHandlePtr rt_active_goal_;
125  control_msgs::GripperCommandResultPtr pre_alloc_result_;
126 
128 
129  // ROS API
131  ActionServerPtr action_server_;
132 
134 
135  void goalCB(GoalHandle gh);
136  void cancelCB(GoalHandle gh);
137  void preemptActiveGoal();
138  void setHoldPosition(const ros::Time& time);
139 
142 
149  void checkForSuccess(const ros::Time& time, double error_position, double current_position, double current_velocity);
150 
151 };
152 
153 } // namespace
154 
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 Fri Feb 3 2023 03:19:12