25 #ifndef ROBOTIQ_3F_GRIPPER_ROS_H 26 #define ROBOTIQ_3F_GRIPPER_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> 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);
55 void handleRawCmd(
const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &
msg);
57 void updateConfig(
const robotiq_3f_gripper_control::Robotiq3FGripperConfig &config);
58 void getCurrentConfig(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config);
79 typedef dynamic_reconfigure::Server<robotiq_3f_gripper_control::Robotiq3FGripperConfig>
ReconfigureServer;
82 robotiq_3f_gripper_control::Robotiq3FGripperConfig
config_;
89 #endif // ROBOTIQ_3F_GRIPPER_ROS_H
ros::ServiceServer emerg_release_srv_
void handleRawCmd(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &msg)
bool handleHalt(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
ros::ServiceServer init_srv_
Services.
ros::Publisher input_status_pub_
Topics.
ros::Duration desired_update_freq_
Settings.
bool handleShutdown(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
boost::recursive_mutex reconfigure_mutex_
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_
ros::Subscriber output_sub_
void getCurrentConfig(robotiq_3f_gripper_control::Robotiq3FGripperConfig &config)
ros::ServiceServer halt_srv_
ros::ServiceServer shutdown_srv_
bool handleReset(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
ros::ServiceServer reset_srv_
dynamic_reconfigure::Server< robotiq_3f_gripper_control::Robotiq3FGripperConfig > ReconfigureServer
Reconfigure.
bool handleInit(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)