bcap_service_test.cpp
Go to the documentation of this file.
1 
25 #include <ros/ros.h>
26 #include "bcap_service/bcap.h"
27 
28 using namespace bcap_service;
29 
30 int main(int argc, char **argv)
31 {
32  if ((argc < 4) || (argc % 2 != 0))
33  {
34  ROS_WARN("Usage: bcap_service_test func_id vt value ...");
35  return 1;
36  }
37 
38  ros::init(argc, argv, "bcap_service_test");
39 
40  ros::NodeHandle node;
41  ros::ServiceClient client = node.serviceClient<bcap>("bcap_service");
42 
43  int i;
44  bcap packet;
45 
46  packet.request.func_id = atoi(argv[1]);
47 
48  for(i = 0; i < (argc - 2) / 2; i++) {
49  variant vnt;
50  vnt.vt = atoi(argv[2 + 2 * i]);
51  vnt.value = argv[3 + 2 * i];
52  packet.request.vntArgs.push_back(vnt);
53  }
54 
55  if (client.call(packet))
56  {
57  ROS_INFO("HRESULT: %X", packet.response.HRESULT);
58  ROS_INFO("vntRet: vt := %d, value := %s", packet.response.vntRet.vt, packet.response.vntRet.value.c_str());
59  }
60  else
61  {
62  ROS_ERROR("Failed to call.");
63  return 1;
64  }
65 
66  return 0;
67 
68 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
#define ROS_WARN(...)
#define ROS_INFO(...)
int main(int argc, char **argv)
#define ROS_ERROR(...)


bcap_service_test
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:24