Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <ros/ros.h>
00038 #include <navcon_msgs/RegisterController.h>
00039
00040 int main (int argc, char **argv)
00041 {
00042 ros::init(argc, argv, "test_ident");
00043 ros::NodeHandle nh;
00044
00045 ros::ServiceClient client = nh.serviceClient<navcon_msgs::RegisterController>("register_controller");
00046 navcon_msgs::RegisterController srv;
00047
00048
00049 std::string manuals[]={"manualX","manualY","manualZ","manualN"};
00050
00051 std::string basics[]={"surge","sway","heave","yaw_rate"};
00052 int basics_dofs[]={0,1,2,5};
00053
00054 for (int i=0; i<4; ++i)
00055 {
00056 srv.request.used_dofs.assign(0);
00057 srv.request.name = basics[i];
00058 srv.request.used_dofs[basics_dofs[i]] = 1;
00059 client.call(srv);
00060
00061 srv.request.used_dofs.assign(0);
00062 srv.request.name = manuals[i];
00063 srv.request.used_dofs[basics_dofs[i]] = 1;
00064 client.call(srv);
00065 }
00066
00067
00068 srv.request.name = "identX";
00069 srv.request.used_dofs.assign(1);
00070
00071 srv.request.used_dofs[5] = 0;
00072 client.call(srv);
00073
00074 srv.request.name = "identY";
00075 srv.request.used_dofs.assign(1);
00076
00077 srv.request.used_dofs[5] = 0;
00078 client.call(srv);
00079
00080 srv.request.name = "identZ";
00081 srv.request.used_dofs.assign(1);
00082 client.call(srv);
00083
00084 srv.request.name = "identN";
00085 srv.request.used_dofs.assign(1);
00086 client.call(srv);
00087
00088 srv.request.used_dofs.assign(0);
00089
00090 srv.request.name = "dp";
00091 srv.request.used_cnt.resize(2);
00092 srv.request.used_cnt[0] = "surge";
00093 srv.request.used_cnt[1] = "sway";
00094 client.call(srv);
00095
00096 srv.request.name = "hdg";
00097 srv.request.used_cnt.resize(1);
00098 srv.request.used_cnt[0] = "yaw_rate";
00099 client.call(srv);
00100
00101 srv.request.name = "depth";
00102 srv.request.used_cnt.resize(1);
00103 srv.request.used_cnt[0] = "heave";
00104 client.call(srv);
00105
00106 srv.request.name = "dpDepth";
00107 srv.request.used_cnt.resize(3);
00108 srv.request.used_cnt[0] = "surge";
00109 srv.request.used_cnt[1] = "sway";
00110 srv.request.used_cnt[2] = "depth";
00111 client.call(srv);
00112
00113 srv.request.name = "dpHdg";
00114 srv.request.used_cnt.resize(3);
00115 srv.request.used_cnt[0] = "surge";
00116 srv.request.used_cnt[1] = "sway";
00117 srv.request.used_cnt[2] = "hdg";
00118 client.call(srv);
00119
00120 srv.request.name = "dpHdgDepth";
00121 srv.request.used_cnt.resize(4);
00122 srv.request.used_cnt[0] = "surge";
00123 srv.request.used_cnt[1] = "sway";
00124 srv.request.used_cnt[2] = "hdg";
00125 srv.request.used_cnt[3] = "depth";
00126 client.call(srv);
00127
00128
00129 return 0;
00130 }
00131
00132
00133