26 #include "bcap_service/bcap.h" 30 int main(
int argc,
char **argv)
32 if ((argc < 4) || (argc % 2 != 0))
34 ROS_WARN(
"Usage: bcap_service_test func_id vt value ...");
38 ros::init(argc, argv,
"bcap_service_test");
46 packet.request.func_id = atoi(argv[1]);
48 for(i = 0; i < (argc - 2) / 2; i++) {
50 vnt.vt = atoi(argv[2 + 2 * i]);
51 vnt.value = argv[3 + 2 * i];
52 packet.request.vntArgs.push_back(vnt);
55 if (client.
call(packet))
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());
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)
int main(int argc, char **argv)