18 int main(
int argc,
char** argv)
21 ros::init(argc, argv,
"gripper_2f_gripper_action_server");
26 std::string gripper_name;
27 private_nh.
param<std::string>(
"gripper_name", gripper_name,
"gripper");
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_);
38 ROS_INFO(
"Initializing Robotiq action server for gripper: %s", gripper_name.c_str());
43 ROS_INFO(
"Robotiq action-server spinning for gripper: %s", gripper_name.c_str());
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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...