4 #include <xarm_gripper/MoveAction.h> 7 int main (
int argc,
char **argv)
15 ROS_INFO(
"Waiting for action server to start.");
19 ROS_INFO(
"Action server started, sending goal.");
21 xarm_gripper::MoveGoal goal;
24 ROS_WARN(
"argment 1: target_pulse, argument 2: pulse_speed, Not fully specified.");
25 ROS_INFO(
"Use default target_pulse: 450, pulse_speed: 1500");
26 goal.target_pulse = 450;
27 goal.pulse_speed = 1500;
31 goal.target_pulse = std::atof(argv[1]);
32 goal.pulse_speed = std::atof(argv[2]);
39 if (finished_before_timeout)
46 ROS_INFO(
"Action did not finish before the time out.");
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string toString() const
int main(int argc, char **argv)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
SimpleClientGoalState getState() const