set_soft_iron_matrix_client.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "microstrain_mips/SetSoftIronMatrix.h"
3 #include <cstdlib>
4 
5 
6 int main(int argc, char **argv){
7 
8  ros::init(argc, argv, "set_soft_iron_matrix_client");
9 
11  ros::ServiceClient client = n.serviceClient<microstrain_mips::SetSoftIronMatrix>("SetSoftIronMatrix");
12  microstrain_mips::SetSoftIronMatrix srv;
13 
14  srv.request.soft_iron_1.x = atoll(argv[1]);
15  srv.request.soft_iron_1.y = atoll(argv[2]);
16  srv.request.soft_iron_1.z = atoll(argv[3]);
17  srv.request.soft_iron_2.x = atoll(argv[4]);
18  srv.request.soft_iron_2.y = atoll(argv[5]);
19  srv.request.soft_iron_2.z = atoll(argv[6]);
20  srv.request.soft_iron_3.x = atoll(argv[7]);
21  srv.request.soft_iron_3.y = atoll(argv[8]);
22  srv.request.soft_iron_3.z = atoll(argv[9]);
23 
24 
25  if (client.call(srv))
26  {
27  if (srv.response.success)
28  {
29  ROS_INFO("success");
30  }
31  }
32  else
33  {
34  ROS_INFO("Failed to call service");
35  }
36  return 0;
37 }
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)
#define ROS_INFO(...)


microstrain_mips
Author(s): Brian Bingham
autogenerated on Sun Dec 22 2019 03:54:45