forked from TechmanRobotInc/tm2_ros2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdemo_send_script.cpp
executable file
·53 lines (43 loc) · 1.57 KB
/
demo_send_script.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
#include "rclcpp/rclcpp.hpp"
#include "tm_msgs/srv/send_script.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
bool send_cmd(std::string cmd, std::shared_ptr<rclcpp::Node> node, rclcpp::Client<tm_msgs::srv::SendScript>::SharedPtr client){
auto request = std::make_shared<tm_msgs::srv::SendScript::Request>();
request->id = "demo";
request->script = cmd;
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return false;
}
RCLCPP_INFO_STREAM(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
}
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
{
if(result.get()->ok){
RCLCPP_INFO_STREAM(rclcpp::get_logger("rclcpp"),"OK");
} else{
RCLCPP_INFO_STREAM(rclcpp::get_logger("rclcpp"),"not OK");
}
} else {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("rclcpp"), "Failed to call service");
}
return true;
}
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("demo_send_script");
rclcpp::Client<tm_msgs::srv::SendScript>::SharedPtr client =
node->create_client<tm_msgs::srv::SendScript>("send_script");
std::string cmd = "PTP(\"JPP\",0,0,90,0,90,0,35,200,0,false)";
send_cmd(cmd, node, client);
rclcpp::shutdown();
return 0;
}