shell.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <cstdio>
3 #include <iostream>
4 #include <memory>
5 #include <stdexcept>
6 #include <string>
7 #include <array>
8 #include <std_msgs/String.h>
9 
10 #include <clover/Execute.h>
11 
13 
14 // TODO: handle timeout
15 bool handle(clover::Execute::Request& req, clover::Execute::Response& res)
16 {
17  ROS_INFO("Execute: %s", req.cmd.c_str());
18 
19  std::array<char, 128> buffer;
20  std::string result;
21 
22  FILE *fp = popen(req.cmd.c_str(), "r");
23 
24  if (fp == NULL) {
25  res.code = clover::Execute::Request::CODE_FAIL;
26  res.output = "popen() failed";
27  return true;
28  }
29 
30  while (fgets(buffer.data(), buffer.size(), fp) != nullptr) {
31  res.output += buffer.data();
32  }
33 
34  res.code = pclose(fp);
35  return true;
36 }
37 
38 
39 int main(int argc, char **argv)
40 {
41  ros::init(argc, argv, "shell");
42  ros::NodeHandle nh, nh_priv("~");
43 
44  timeout = ros::Duration(nh_priv.param("timeout", 3.0));
45 
46  auto gt_serv = nh.advertiseService("exec", &handle);
47 
48  ROS_INFO("shell: ready");
49  ros::spin();
50 }
bool handle(clover::Execute::Request &req, clover::Execute::Response &res)
Definition: shell.cpp:15
ros::NodeHandle nh
ros::Duration timeout
Definition: shell.cpp:12
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
uint8_t result
#define ROS_INFO(...)
string buffer
ROSCPP_DECL void spin()
int main(int argc, char **argv)
Definition: shell.cpp:39


clover
Author(s): Oleg Kalachev , Artem Smirnov
autogenerated on Mon Feb 28 2022 22:08:29