fibonacci_callback_client.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003 #include <actionlib_tutorials/FibonacciAction.h>
00004 
00005 using namespace actionlib_tutorials;
00006 typedef actionlib::SimpleActionClient<FibonacciAction> Client;
00007 
00008 // Called once when the goal completes
00009 void doneCb(const actionlib::SimpleClientGoalState& state,
00010             const FibonacciResultConstPtr& result)
00011 {
00012   ROS_INFO("Finished in state [%s]", state.toString().c_str());
00013   ROS_INFO("Answer: %i", result->sequence.back());
00014   ros::shutdown();
00015 }
00016 
00017 // Called once when the goal becomes active
00018 void activeCb()
00019 {
00020   ROS_INFO("Goal just went active");
00021 }
00022 
00023 // Called every time feedback is received for the goal
00024 void feedbackCb(const FibonacciFeedbackConstPtr& feedback)
00025 {
00026   ROS_INFO("Got Feedback of length %lu", feedback->sequence.size());
00027 }
00028 
00029 int main (int argc, char **argv)
00030 {
00031   ros::init(argc, argv, "test_fibonacci_callback");
00032 
00033   // Create the action client
00034   Client ac("fibonacci", true);
00035 
00036   ROS_INFO("Waiting for action server to start.");
00037   ac.waitForServer();
00038   ROS_INFO("Action server started, sending goal.");
00039 
00040   // Send Goal
00041   FibonacciGoal goal;
00042   goal.order = 20;
00043   ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
00044 
00045   ros::spin();
00046   return 0;
00047 }


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Thu Jun 6 2019 21:11:25