3 #include <actionlib_tutorials/FibonacciAction.h> 10 const FibonacciResultConstPtr&
result)
13 ROS_INFO(
"Answer: %i", result->sequence.back());
24 void feedbackCb(
const FibonacciFeedbackConstPtr& feedback)
26 ROS_INFO(
"Got Feedback of length %lu", feedback->sequence.size());
29 int main (
int argc,
char **argv)
31 ros::init(argc, argv,
"test_fibonacci_callback");
34 Client ac(
"fibonacci",
true);
36 ROS_INFO(
"Waiting for action server to start.");
38 ROS_INFO(
"Action server started, sending goal.");
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void feedbackCb(const FibonacciFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
std::string toString() const
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
actionlib::SimpleActionClient< FibonacciAction > Client
ROSCPP_DECL void shutdown()
void doneCb(const actionlib::SimpleClientGoalState &state, const FibonacciResultConstPtr &result)