-
Notifications
You must be signed in to change notification settings - Fork 6
/
gsl_server_call.cpp
58 lines (45 loc) · 1.77 KB
/
gsl_server_call.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <gsl_actions/action/do_gsl.hpp>
#include <std_msgs/msg/string.hpp>
using DoGSL = gsl_actions::action::DoGSL;
template <typename T> static T getParam(rclcpp::Node::SharedPtr node, const std::string& name, T defaultValue)
{
if (node->has_parameter(name))
return node->get_parameter_or<T>(name, defaultValue);
else
return node->declare_parameter<T>(name, defaultValue);
}
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::Node::SharedPtr call_node = std::make_shared<rclcpp::Node>("gsl_call");
auto resetSimulatorPub = call_node->create_publisher<std_msgs::msg::String>("/basic_sim/reset", rclcpp::QoS(1).transient_local());
{
std_msgs::msg::String msg;
msg.data = "all";
resetSimulatorPub->publish(msg);
}
std::string method = getParam<std::string>(call_node, "method", "surge_cast");
auto action_client = rclcpp_action::create_client<DoGSL>(call_node, "gsl_server");
using namespace std::chrono_literals;
while (rclcpp::ok() && !action_client->wait_for_action_server(10s))
{
RCLCPP_INFO(call_node->get_logger(), "Waiting for action server to start.");
}
RCLCPP_INFO(call_node->get_logger(), "Action server started, sending goal.");
DoGSL::Goal goal;
goal.gsl_method = method;
rclcpp_action::Client<DoGSL>::SendGoalOptions options;
bool done = false;
options.result_callback = [&done](const rclcpp_action::ClientGoalHandle<DoGSL>::WrappedResult& result) { done = true; };
action_client->async_send_goal(goal);
rclcpp::Rate rate(1);
while (!done)
{
rclcpp::spin_some(call_node);
rate.sleep();
}
RCLCPP_INFO(call_node->get_logger(), "GSL finished");
return 0;
}