4 #include <control_msgs/GripperCommandAction.h> 6 int main (
int argc,
char **argv)
8 ros::init(argc, argv,
"test_robotiq_2f_gripper_action_server");
12 std::string gripper_name;
13 pnh.
param<std::string>(
"gripper_name", gripper_name,
"gripper");
19 ROS_INFO(
"Waiting for action server to start.");
23 ROS_INFO(
"Action server started, sending goal.");
26 goal.command.position = -0.01;
27 goal.command.max_effort = 100.0;
31 bool finished_before_timeout = ac.waitForResult(
ros::Duration(30.0));
33 if (finished_before_timeout)
39 ROS_INFO(
"Action did not finish before the time out.");
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string toString() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
control_msgs::GripperCommandGoal GripperCommandGoal