fibonacci_class_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 class MyNode
9 {
10 public:
11  MyNode() : ac("fibonacci", true)
12  {
13  ROS_INFO("Waiting for action server to start.");
14  ac.waitForServer();
15  ROS_INFO("Action server started, sending goal.");
16  }
17 
18  void doStuff(int order)
19  {
20  FibonacciGoal goal;
21  goal.order = order;
22 
23  // Need boost::bind to pass in the 'this' pointer
24  ac.sendGoal(goal,
25  boost::bind(&MyNode::doneCb, this, _1, _2),
28 
29  }
30 
32  const FibonacciResultConstPtr& result)
33  {
34  ROS_INFO("Finished in state [%s]", state.toString().c_str());
35  ROS_INFO("Answer: %i", result->sequence.back());
36  ros::shutdown();
37  }
38 
39 private:
41 };
42 
43 int main (int argc, char **argv)
44 {
45  ros::init(argc, argv, "test_fibonacci_class_client");
46  MyNode my_node;
47  my_node.doStuff(10);
48  ros::spin();
49  return 0;
50 }
fibonacci_client.result
def result
Definition: fibonacci_client.py:41
MyNode::doStuff
void doStuff(int order)
Definition: fibonacci_class_client.cpp:18
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
actionlib::SimpleClientGoalState
Client
actionlib::SimpleActionClient< FibonacciAction > Client
Definition: fibonacci_class_client.cpp:6
ros::shutdown
ROSCPP_DECL void shutdown()
MyNode::ac
Client ac
Definition: fibonacci_class_client.cpp:40
actionlib::SimpleActionClient
MyNode::doneCb
void doneCb(const actionlib::SimpleClientGoalState &state, const FibonacciResultConstPtr &result)
Definition: fibonacci_class_client.cpp:31
simple_action_client.h
actionlib::SimpleActionClient< actionlib::TestAction >::SimpleActiveCallback
boost::function< void()> SimpleActiveCallback
actionlib::SimpleActionClient< actionlib::TestAction >::SimpleFeedbackCallback
boost::function< void(const FeedbackConstPtr &feedback)> SimpleFeedbackCallback
MyNode
Definition: fibonacci_class_client.cpp:8
actionlib::SimpleClientGoalState::toString
std::string toString() const
ros::spin
ROSCPP_DECL void spin()
main
int main(int argc, char **argv)
Definition: fibonacci_class_client.cpp:43
MyNode::MyNode
MyNode()
Definition: fibonacci_class_client.cpp:11
ROS_INFO
#define ROS_INFO(...)


actionlib_tutorials
Author(s): Melonee Wise
autogenerated on Wed Mar 2 2022 00:05:48