test_exec.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the LABUST nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *
00034 *  Author: Dula Nad
00035 *  Created: 01.02.2013.
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   //Add manual
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   //Add surge, sway, heave, yaw_rate controllers.
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         //velocity controllers
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           //tau manual
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           //nu manual
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           //identification
00079           navcon_msgs::RegisterController srv3;
00080           srv3.request.name = ident[i];
00081           //srv3.request.used_dofs.assign(1);
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           //Pose controllers
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   //Underactuated dp
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   //Virtual target
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   //LF target
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   //LF underactuated
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   //exit
00132   return 0;
00133 }
00134 
00135 
00136 


labust_execution
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:25