parallel_gripper.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fetch Robotics Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Fetch Robotics Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // Author: Michael Ferguson
36 
37 #ifndef ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H
38 #define ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H
39 
40 #include <string>
41 #include <vector>
42 
43 #include <ros/ros.h>
44 #include <robot_controllers/pid.h>
48 #include <control_msgs/GripperCommandAction.h>
50 
51 namespace robot_controllers
52 {
53 
59 {
61 
62 public:
64  initialized_(false),
67 
75  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
76 
82  virtual bool start();
83 
91  virtual bool stop(bool force);
92 
99  virtual bool reset();
100 
106  virtual void update(const ros::Time& now, const ros::Duration& dt);
107 
109  virtual std::string getType()
110  {
111  return "robot_controllers/ParallelGripperController";
112  }
113 
115  virtual std::vector<std::string> getCommandedNames();
116 
118  virtual std::vector<std::string> getClaimedNames();
119 
120 private:
121  void executeCb(const control_msgs::GripperCommandGoalConstPtr& goal);
122 
125 
128 
131 
134 };
135 
136 } // namespace robot_controllers
137 
138 #endif // ROBOT_CONTROLLERS_PARALLEL_GRIPPER_H
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > server_t
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
Controller for a parallel jaw gripper, is really only intended for use in simulation.
virtual std::string getType()
Get the type of this controller.
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
goal
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
void executeCb(const control_msgs::GripperCommandGoalConstPtr &goal)


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39