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 manuals[]={"manualX","manualY","manualZ","manualN"};
00050   //Add surge, sway, heave, yaw_rate controllers.
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   //Add identifications: surge, sway, heave, yaw
00068   srv.request.name = "identX";
00069   srv.request.used_dofs.assign(1);
00070   //Let heading DOF be free ?
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   //Let heading DOF be free ?
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   //Add complex controllers: dp, hdg, depth, dp+depth, dp+hdg
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   //exit
00129   return 0;
00130 }
00131 
00132 
00133 


labust_execution
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:24