fibonacci_callback_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <actionlib_tutorials/FibonacciAction.h>
4 
5 using namespace actionlib_tutorials;
7 
8 // Called once when the goal completes
10  const FibonacciResultConstPtr& result)
11 {
12  ROS_INFO("Finished in state [%s]", state.toString().c_str());
13  ROS_INFO("Answer: %i", result->sequence.back());
14  ros::shutdown();
15 }
16 
17 // Called once when the goal becomes active
18 void activeCb()
19 {
20  ROS_INFO("Goal just went active");
21 }
22 
23 // Called every time feedback is received for the goal
24 void feedbackCb(const FibonacciFeedbackConstPtr& feedback)
25 {
26  ROS_INFO("Got Feedback of length %lu", feedback->sequence.size());
27 }
28 
29 int main (int argc, char **argv)
30 {
31  ros::init(argc, argv, "test_fibonacci_callback");
32 
33  // Create the action client
34  Client ac("fibonacci", true);
35 
36  ROS_INFO("Waiting for action server to start.");
37  ac.waitForServer();
38  ROS_INFO("Action server started, sending goal.");
39 
40  // Send Goal
41  FibonacciGoal goal;
42  goal.order = 20;
43  ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
44 
45  ros::spin();
46  return 0;
47 }
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
#define ROS_INFO(...)
ROSCPP_DECL void spin()
void activeCb()
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)


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Sat Apr 4 2020 03:47:16