labustMission.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * labustMission.hpp
00003  *
00004  *  Created on: Apr 10, 2014
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010 * Software License Agreement (BSD License)
00011 *
00012 *  Copyright (c) 2014, LABUST, UNIZG-FER
00013 *  All rights reserved.
00014 *
00015 *  Redistribution and use in source and binary forms, with or without
00016 *  modification, are permitted provided that the following conditions
00017 *  are met:
00018 *
00019 *   * Redistributions of source code must retain the above copyright
00020 *     notice, this list of conditions and the following disclaimer.
00021 *   * Redistributions in binary form must reproduce the above
00022 *     copyright notice, this list of conditions and the following
00023 *     disclaimer in the documentation and/or other materials provided
00024 *     with the distribution.
00025 *   * Neither the name of the LABUST nor the names of its
00026 *     contributors may be used to endorse or promote products derived
00027 *     from this software without specific prior written permission.
00028 *
00029 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040 *  POSSIBILITY OF SUCH DAMAGE.
00041 *********************************************************************/
00042 
00043 #ifndef LABUSTMISSION_HPP_
00044 #define LABUSTMISSION_HPP_
00045 
00046 /*********************************************************************
00047  *** Common includes
00048  ********************************************************************/
00049 
00050 #include <string>
00051 
00052 #include <ros/ros.h>
00053 #include <boost/bind.hpp>
00054 #include <boost/thread.hpp>
00055 
00056 #include <labust_mission/utils.hpp>
00057 
00058 #include <std_msgs/Bool.h>
00059 #include <std_msgs/String.h>
00060 #include <std_msgs/UInt16.h>
00061 #include <std_msgs/Float64MultiArray.h>
00062 
00063 #include <misc_msgs/SendPrimitive.h>
00064 #include <misc_msgs/Go2PointFA.h>
00065 #include <misc_msgs/Go2PointUA.h>
00066 #include <misc_msgs/DynamicPositioning.h>
00067 #include <misc_msgs/CourseKeepingFA.h>
00068 #include <misc_msgs/CourseKeepingUA.h>
00069 #include <misc_msgs/ISO.h>
00070 #include <misc_msgs/ExternalEvent.h>
00071 #include <misc_msgs/MissionSetup.h>
00072 #include <misc_msgs/DataEventsContainer.h>
00073 #include <misc_msgs/EvaluateExpression.h>
00074 
00075 #include <auv_msgs/NED.h>
00076 #include <auv_msgs/NavSts.h>
00077 #include <auv_msgs/DecimalLatLon.h>
00078 
00079 
00080 /*********************************************************************
00081  *** Common global variables
00082  ********************************************************************/
00083 
00084 enum {X = 0, Y, Z, T};
00085 
00086 enum {none = 0,
00087                 placeholder,
00088                 go2point_FA,
00089                 go2point_UA,
00090                 go2point_FA_hdg,
00091                 dynamic_positioning,
00092                 course_keeping_FA,
00093                 course_keeping_UA,
00094                 course_keeping_FA_hdg,
00095                 iso,
00096                 path_following,
00097                 pointer,
00098                 primitiveNum};
00099 
00100 const char *PRIMITIVES[] = {"none",
00101                                                                 "placeholder",
00102                                                                 "go2point_FA",
00103                                                                 "go2point_UA",
00104                                                                 "go2point_FA_hdg",
00105                                                                 "dynamic_positioning",
00106                                                                 "course_keeping_FA",
00107                                                                 "course_keeping_UA",
00108                                                                 "course_keeping_FA_hdg",
00109                                                                 "iso",
00110                                                                 "path_following",
00111                                                                 "pointer"};
00112 
00113 enum {u=0, v, w, r, x, y, z, psi, x_var, y_var, z_var, psi_var, alt, stateHatNum}; /* Enumeration used for DataManager */
00114 const char *stateVarNames[] = {"u", "v", "w", "r", "x", "y", "z", "psi", "x_var", "y_var", "z_var", "psi_var", "alt"};
00115 
00116 const char *pl_placeholder[] = {"\0"};
00117 const char *pl_go2point_FA[] = {"north","east","speed","victory_radius","\0"};
00118 const char *pl_go2point_UA[] = {"north","east","speed","victory_radius","\0"};
00119 const char *pl_go2point_FA_hdg[] = {"north","east","heading","speed","victory_radius","\0"};
00120 const char *pl_dynamic_positioning[] = {"north","east","heading","timeout","\0"};
00121 const char *pl_course_keeping_FA[] = {"course","speed","timeout","\0"};
00122 const char *pl_course_keeping_FA_hdg[] = {"course","speed","heading","timeout","\0"};
00123 const char *pl_iso[] = {"dof","command","hysteresis","reference","sampling_rate","\0"};
00124 const char *pl_path_following[] = {"point","\0"};
00125 const char *pl_pointer[] = {"radius_topic","center_topic","target_topic","\0"};
00126 const char *pl_course_keeping_UA[] = {"course","speed","timeout","\0"};
00127 
00128 struct PrimitiveParams{
00129         PrimitiveParams(){
00130 
00131         std::vector<std::string> tmp;
00132                 std::string tmp_str;
00133                 int i = 0;
00134                  for(i = 0; strcmp(pl_go2point_FA[i],"\0") != 0; i++){
00135                          tmp_str.assign(pl_go2point_FA[i]);
00136                          tmp.push_back(tmp_str);
00137                  }
00138                 primitive_params.insert(std::pair<int,std::vector<std::string> >(go2point_FA,tmp));
00139 
00140                 tmp.clear();
00141                  for(i = 0; strcmp(pl_go2point_UA[i],"\0") != 0; i++){
00142                          tmp_str.assign(pl_go2point_UA[i]);
00143                          tmp.push_back(tmp_str);
00144                  }
00145                 primitive_params.insert(std::pair<int,std::vector<std::string> >(go2point_UA,tmp));
00146 
00147                 tmp.clear();
00148                  for(i = 0; strcmp(pl_go2point_FA_hdg[i],"\0") != 0; i++){
00149                          tmp_str.assign(pl_go2point_FA_hdg[i]);
00150                          tmp.push_back(tmp_str);
00151                  }
00152                 primitive_params.insert(std::pair<int,std::vector<std::string> >(go2point_FA_hdg,tmp));
00153 
00154                 tmp.clear();
00155                  for(i = 0; strcmp(pl_dynamic_positioning[i],"\0") !=0; i++){
00156                          tmp_str.assign(pl_dynamic_positioning[i]);
00157                          tmp.push_back(tmp_str);
00158                  }
00159                 primitive_params.insert(std::pair<int,std::vector<std::string> >(dynamic_positioning,tmp));
00160 
00161                 tmp.clear();
00162                  for(i = 0; strcmp(pl_course_keeping_FA[i],"\0") != 0; i++){
00163                          tmp_str.assign(pl_course_keeping_FA[i]);
00164                          tmp.push_back(tmp_str);
00165                  }
00166                 primitive_params.insert(std::pair<int,std::vector<std::string> >(course_keeping_FA,tmp));
00167 
00168                 tmp.clear();
00169                  for(i = 0; strcmp(pl_course_keeping_UA[i],"\0") != 0; i++){
00170                          tmp_str.assign(pl_course_keeping_UA[i]);
00171                          tmp.push_back(tmp_str);
00172                  }
00173 
00174                  primitive_params.insert(std::pair<int,std::vector<std::string> >(course_keeping_UA,tmp));
00175 
00176                 tmp.clear();
00177                  for(i = 0; strcmp(pl_iso[i],"\0") != 0; i++){
00178                          tmp_str.assign(pl_iso[i]);
00179                          tmp.push_back(tmp_str);
00180                  }
00181                  primitive_params.insert(std::pair<int,std::vector<std::string> >(iso,tmp));
00182 
00183                 tmp.clear();
00184                  for(i = 0; strcmp(pl_path_following[i],"\0") != 0; i++){
00185                          tmp_str.assign(pl_path_following[i]);
00186                          tmp.push_back(tmp_str);
00187                  }
00188                 primitive_params.insert(std::pair<int,std::vector<std::string> >(path_following,tmp));
00189 
00190                 tmp.clear();
00191                  for(i = 0; strcmp(pl_iso[i],"\0") != 0; i++){
00192                          tmp_str.assign(pl_pointer[i]);
00193                          tmp.push_back(tmp_str);
00194                  }
00195                 primitive_params.insert(std::pair<int,std::vector<std::string> >(pointer,tmp));
00196 
00197                 tmp.clear();
00198                  for(int i = 0; strcmp(pl_placeholder[i],"\0") != 0; i++){
00199                          tmp_str.assign(pl_placeholder[i]);
00200                          tmp.push_back(tmp_str);
00201                  }
00202                 primitive_params[placeholder] = tmp;
00203 
00204         }
00205 
00206         ~PrimitiveParams(){}
00207 
00208         std::map<int,  std::vector<std::string> > primitive_params;
00209 };
00210 
00211 using namespace std;
00212 
00213 #endif /* LABUSTMISSION_HPP_ */


labust_mission
Author(s): Filip Mandic
autogenerated on Fri Aug 28 2015 11:23:04