src
shape_client.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
#include <
actionlib/client/simple_action_client.h
>
3
#include <
actionlib/client/terminal_state.h
>
4
#include <turtle_actionlib/ShapeAction.h>
5
6
int
main
(
int
argc,
char
**argv)
7
{
8
ros::init
(argc, argv,
"test_shape"
);
9
10
// create the action client
11
// true causes the client to spin it's own thread
12
actionlib::SimpleActionClient<turtle_actionlib::ShapeAction>
ac(
"turtle_shape"
,
true
);
13
14
ROS_INFO
(
"Waiting for action server to start."
);
15
// wait for the action server to start
16
ac.
waitForServer
();
//will wait for infinite time
17
18
ROS_INFO
(
"Action server started, sending goal."
);
19
// send a goal to the action
20
turtle_actionlib::ShapeGoal goal;
21
goal.edges = 5;
22
goal.radius = 1.3;
23
ac.
sendGoal
(goal);
24
25
//wait for the action to return
26
bool
finished_before_timeout = ac.
waitForResult
(
ros::Duration
(40.0));
27
28
if
(finished_before_timeout)
29
{
30
actionlib::SimpleClientGoalState
state = ac.
getState
();
31
ROS_INFO
(
"Action finished: %s"
,state.
toString
().c_str());
32
}
33
else
34
ROS_INFO
(
"Action did not finish before the time out."
);
35
36
//exit
37
return
0;
38
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
terminal_state.h
actionlib::SimpleClientGoalState
actionlib::SimpleActionClient
simple_action_client.h
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
main
int main(int argc, char **argv)
Definition:
shape_client.cpp:6
actionlib::SimpleActionClient::waitForResult
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
actionlib::SimpleClientGoalState::toString
std::string toString() const
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
ROS_INFO
#define ROS_INFO(...)
ros::Duration
turtle_actionlib
Author(s): Melonee Wise
autogenerated on Wed Mar 2 2022 00:05:51