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 manualPos[]={"manual_x","manual_y","manual_z","manual_roll", "manual_pitch", "manual_yaw"};
00050 std::string manualNu[]={"manual_u","manual_v","manual_w","manual_p", "manual_q", "manual_r"};
00051 std::string manuals[]={"manualX","manualY","manualZ","manualK", "manualM", "manualN"};
00052
00053 std::string basics[]={"surge","sway","heave","roll_rate","pitch_rate","yaw_rate"};
00054 std::string ident[]={"identX","identY","identZ","identK","identM","identN"};
00055 std::string pose_cnt[]={"fadp","fadp","depth","roll","pitch","heading"};
00056 int basics_dofs[]={0,1,2,3,4,5};
00057
00058 for (int i=0; i<6; ++i)
00059 {
00060
00061 srv.request.used_dofs.assign(0);
00062 srv.request.name = basics[i];
00063 srv.request.used_dofs[basics_dofs[i]] = 1;
00064 client.call(srv);
00065
00066
00067 srv.request.used_dofs.assign(0);
00068 srv.request.name = manuals[i];
00069 srv.request.used_dofs[basics_dofs[i]] = 1;
00070 client.call(srv);
00071
00072
00073 navcon_msgs::RegisterController srv2;
00074 srv2.request.name = manualNu[i];
00075 srv2.request.used_cnt.push_back(basics[i]);
00076 client.call(srv2);
00077
00078
00079 navcon_msgs::RegisterController srv3;
00080 srv3.request.name = ident[i];
00081
00082 srv3.request.used_dofs[2] = 0;
00083 srv3.request.used_dofs[5] = 0;
00084 srv3.request.used_dofs[i] = 1;
00085 client.call(srv3);
00086
00087
00088 navcon_msgs::RegisterController srv4;
00089 srv4.request.name = pose_cnt[i];
00090 srv4.request.used_cnt.push_back(basics[i]);
00091 if (i == 1) srv4.request.used_cnt.push_back(basics[i-1]);
00092 if (i != 0) client.call(srv4);
00093
00094 std::cout<<"finished no:"<<i<<std::endl;
00095 }
00096
00097
00098 srv.request.used_dofs.assign(0);
00099 srv.request.used_cnt.clear();
00100 srv.request.name = "uadp";
00101 srv.request.used_cnt.push_back("surge");
00102 srv.request.used_cnt.push_back("heading");
00103 client.call(srv);
00104
00105 std::cout<<"Added dp."<<std::endl;
00106
00107
00108 srv.request.used_dofs.assign(0);
00109 srv.request.used_cnt.clear();
00110 srv.request.name = "vt";
00111 srv.request.used_cnt.push_back("surge");
00112 srv.request.used_cnt.push_back("yaw_rate");
00113 client.call(srv);
00114 std::cout<<"Added dp."<<std::endl;
00115
00116 srv.request.used_dofs.assign(0);
00117 srv.request.used_cnt.clear();
00118 srv.request.name = "falf";
00119 srv.request.used_cnt.push_back("surge");
00120 srv.request.used_cnt.push_back("sway");
00121 srv.request.used_cnt.push_back("heading");
00122 client.call(srv);
00123
00124 srv.request.used_dofs.assign(0);
00125 srv.request.used_cnt.clear();
00126 srv.request.name = "ualf";
00127 srv.request.used_cnt.push_back("surge");
00128 srv.request.used_cnt.push_back("yaw_rate");
00129 client.call(srv);
00130
00131
00132 return 0;
00133 }
00134
00135
00136