robotiq_3f_gripper_ros.h
Go to the documentation of this file.
1 // Copyright (c) 2016, Toyota Research Institute. All rights reserved.
2 
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 
6 // 1. Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 
9 // 2. Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 
13 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
14 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
15 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
16 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
17 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
19 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
20 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
21 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
22 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
23 // POSSIBILITY OF SUCH DAMAGE.
24 
25 #ifndef ROBOTIQ_3F_GRIPPER_ROS_H
26 #define ROBOTIQ_3F_GRIPPER_ROS_H
27 
28 #include <ros/ros.h>
29 #include <std_srvs/Trigger.h>
30 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotInput.h>
31 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotOutput.h>
33 #include <dynamic_reconfigure/server.h>
34 #include <robotiq_3f_gripper_control/Robotiq3FGripperConfig.h>
35 
37 {
39 {
40 public:
42  boost::shared_ptr<robotiq_3f_gripper_control::Robotiq3FGripperAPI> driver, std::vector<std::string> joint_names,
43  ros::Duration desired_update_freq);
44 
45  void publish();
46 
47  bool handleInit(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp);
48  bool handleReset(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp);
49  bool handleHalt(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp);
50  bool handleEmergRelease(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp);
51  bool handleShutdown(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp);
52 
53  void handleReconfigure(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config, uint32_t level=0);
54 
55  void handleRawCmd(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &msg);
56 
57  void updateConfig(const robotiq_3f_gripper_control::Robotiq3FGripperConfig &config);
58  void getCurrentConfig(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config);
59 
60 private:
63 
70 
74 
77 
79  typedef dynamic_reconfigure::Server<robotiq_3f_gripper_control::Robotiq3FGripperConfig> ReconfigureServer;
81  boost::recursive_mutex reconfigure_mutex_;
82  robotiq_3f_gripper_control::Robotiq3FGripperConfig config_;
83 
84  robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput input_status_msg_;
85 
86 };
87 } //end namespace robotiq_3f_gripper_control
88 
89 #endif // ROBOTIQ_3F_GRIPPER_ROS_H
msg
void handleRawCmd(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &msg)
bool handleHalt(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
unsigned int uint32_t
bool handleShutdown(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
void updateConfig(const robotiq_3f_gripper_control::Robotiq3FGripperConfig &config)
Robotiq3FGripperROS(ros::NodeHandle &nh, boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperAPI > driver, std::vector< std::string > joint_names, ros::Duration desired_update_freq)
boost::shared_ptr< ReconfigureServer > reconfigure_
void handleReconfigure(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config, uint32_t level=0)
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput input_status_msg_
robotiq_3f_gripper_control::Robotiq3FGripperConfig config_
bool handleEmergRelease(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperAPI > driver_
void getCurrentConfig(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config)
bool handleReset(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
dynamic_reconfigure::Server< robotiq_3f_gripper_control::Robotiq3FGripperConfig > ReconfigureServer
Reconfigure.
bool handleInit(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)


robotiq_3f_gripper_control
Author(s): Nicolas Lauzier (Robotiq inc.), Allison Thackston
autogenerated on Tue Jun 1 2021 02:29:58