4 #include <actionlib_tutorials/FibonacciAction.h> 6 int main (
int argc,
char **argv)
14 ROS_INFO(
"Waiting for action server to start.");
18 ROS_INFO(
"Action server started, sending goal.");
20 actionlib_tutorials::FibonacciGoal goal;
27 if (finished_before_timeout)
32 std::stringstream result_string;
33 std::copy(result.sequence.begin(), result.sequence.end(),
34 std::ostream_iterator<int>(result_string,
" "));
35 ROS_INFO(
"Action result: %s", result_string.str().c_str());
38 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
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
int main(int argc, char **argv)
SimpleClientGoalState getState() const
ResultConstPtr getResult() const