robotiq_2f_gripper_action_server_node.cpp
Go to the documentation of this file.
2 
3 namespace
4 {
5  // Defines a default for the c2 model 85 gripper
7  {
9  params.min_gap_ = -.017;
10  params.max_gap_ = 0.085;
11  params.min_effort_ = 40.0; // This is a guess. Could not find data with quick search.
12  params.max_effort_ = 100.0;
13 
14  return params;
15  }
16 }
17 
18 int main(int argc, char** argv)
19 {
20  // Can be renamed with standard ROS-node launch interface
21  ros::init(argc, argv, "gripper_2f_gripper_action_server");
22 
23  // Private Note Handle for retrieving parameter arguments to the server
24  ros::NodeHandle private_nh("~");
25 
26  std::string gripper_name;
27  private_nh.param<std::string>("gripper_name", gripper_name, "gripper");
28 
29  // Fill out 2F-Gripper Params
31 
32  // Min because fingers can push forward before the mechanical stops are reached
33  private_nh.param<double>("min_gap", cparams.min_gap_, cparams.min_gap_);
34  private_nh.param<double>("max_gap", cparams.max_gap_, cparams.max_gap_);
35  private_nh.param<double>("min_effort", cparams.min_effort_, cparams.min_effort_);
36  private_nh.param<double>("max_effort", cparams.max_effort_, cparams.max_effort_);
37 
38  ROS_INFO("Initializing Robotiq action server for gripper: %s", gripper_name.c_str());
39 
40  // The name of the gripper -> this server communicates over name/inputs and name/outputs
42 
43  ROS_INFO("Robotiq action-server spinning for gripper: %s", gripper_name.c_str());
44  ros::spin();
45 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL void spin()
The Robotiq2FGripperActionServer class. Takes as arguments the name of the gripper it is to command...
Structure containing the parameters necessary to translate GripperCommand actions to register-based c...


robotiq_2f_gripper_action_server
Author(s): Jonathan Meyer
autogenerated on Tue Jun 1 2021 02:29:56