primitiveManager.hpp
Go to the documentation of this file.
00001 //TODO Dokumentiraj prototipe funkcija
00002 /*********************************************************************
00003  * PrimitiveManager.hpp
00004  *
00005  *  Created on: Jul 13, 2015
00006  *      Author: Filip Mandic
00007  *
00008  ********************************************************************/
00009 
00010 /*********************************************************************
00011 * Software License Agreement (BSD License)
00012 *
00013 *  Copyright (c) 2015, LABUST, UNIZG-FER
00014 *  All rights reserved.
00015 *
00016 *  Redistribution and use in source and binary forms, with or without
00017 *  modification, are permitted provided that the following conditions
00018 *  are met:
00019 *
00020 *   * Redistributions of source code must retain the above copyright
00021 *     notice, this list of conditions and the following disclaimer.
00022 *   * Redistributions in binary form must reproduce the above
00023 *     copyright notice, this list of conditions and the following
00024 *     disclaimer in the documentation and/or other materials provided
00025 *     with the distribution.
00026 *   * Neither the name of the LABUST nor the names of its
00027 *     contributors may be used to endorse or promote products derived
00028 *     from this software without specific prior written permission.
00029 *
00030 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00031 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00032 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00033 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00034 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00035 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00036 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00037 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00038 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00039 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00040 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00041 *  POSSIBILITY OF SUCH DAMAGE.
00042 *********************************************************************/
00043 
00044 #ifndef PRIMITIVEMANAGER_HPP_
00045 #define PRIMITIVEMANAGER_HPP_
00046 
00047 /*********************************************************************
00048  *** Includes
00049  ********************************************************************/
00050 
00051 #include <cmath>
00052 
00053 //#include <auv_msgs/NavSts.h>
00054 #include <auv_msgs/Bool6Axis.h>
00055 #include <navcon_msgs/EnableControl.h>
00056 #include <navcon_msgs/ConfigureAxes.h>
00057 #include <navcon_msgs/ConfigureVelocityController.h>
00058 
00059 #include <labust_mission/labustMission.hpp>
00060 #include <labust_mission/lowLevelConfigure.hpp>
00061 #include <labust/primitive/PrimitiveCall.hpp>
00062 #include <labust_mission/utils.hpp>
00063 
00064 //#include <actionlib/client/simple_action_client.h>
00065 //#include <actionlib/client/terminal_state.h>
00066 
00067 #include <navcon_msgs/CourseKeepingAction.h>
00068 #include <navcon_msgs/DynamicPositioningAction.h>
00069 #include <navcon_msgs/GoToPointAction.h>
00070 #include <navcon_msgs/DOFIdentificationAction.h>
00071 
00072 /*********************************************************************
00073  *** ControllerManager class definition
00074  *********************************************************************/
00075 
00076 namespace labust
00077 {
00078         namespace controller
00079         {
00080 
00081                 class PrimitiveManager {
00082 
00083                 public:
00084 
00085                         /*********************************************************
00086                          *** Class functions
00087                          ********************************************************/
00088 
00089                         /* Constructor */
00090                         PrimitiveManager();
00091 
00092                         /*********************************************************
00093                          *** Primitive function calls
00094                          ********************************************************/
00095 
00096                         /* Go to point fully actuated primitive */
00097                         void go2point_FA_hdg(bool enable, double north1, double east1, double north2, double east2, double speed, double heading, double radius);
00098 
00099                         /* Go to point fully actuated primitive */
00100                         void go2point_FA(bool enable, double north1, double east1, double north2, double east2, double speed, double radius);
00101 
00102                         /* Go to point underactuated primitive */
00103                         void go2point_UA(bool enable, double north1, double east1, double north2, double east2, double speed, double radius);
00104 
00105                         /* Dynamic positioning primitive */
00106                         void dynamic_positioning(bool enable, double north, double east, double heading);
00107 
00108                         /* Course keeping fully actuated  primitive */
00109                         void course_keeping_FA(bool enable, double course, double speed, double heading);
00110 
00111                         /* Course keeping underactuated  primitive */
00112                         void course_keeping_UA(bool enable, double course, double speed);
00113 
00114                         /* Self-oscillations identification */
00115                         void ISOprimitive(bool enable, int dof, double command, double hysteresis, double reference, double sampling_rate);
00116 
00117                         /*********************************************************
00118                          *** Class variables
00119                          ********************************************************/
00120 
00121                 private:
00122 
00123                         labust::primitive::PrimitiveCallGo2Point Go2Point;
00124                         labust::primitive::PrimitiveCallCourseKeeping CourseKeeping;
00125                         labust::primitive::PrimitiveCallDynamicPositioning DynamicPositioning;
00126                         labust::primitive::PrimitiveCallDOFIdentification DOFIdentification;
00127 
00128                         labust::LowLevelConfigure LLcfg;
00129 
00130                 };
00131         }
00132 }
00133 
00134 using namespace labust::controller;
00135 
00136         /*
00137          * Constructor
00138          */
00139         PrimitiveManager::PrimitiveManager()
00140         {
00141 
00142         }
00143 
00144         /*********************************************************
00145          *** Controller primitives masks
00146          ********************************************************/
00147         /*
00148          * Course keeping fully actuated primitive
00149          */
00150         void PrimitiveManager::go2point_FA_hdg(bool enable, double north1, double east1, double north2, double east2, double speed, double heading, double radius)
00151         {
00152                 typedef navcon_msgs::GoToPointGoal Goal;
00153                 if(enable)
00154                 {
00155                         Goal goal;
00156 
00157                         goal.ref_type = Goal::CONSTANT;
00158                         goal.subtype = Goal::GO2POINT_FA_HDG;
00159 
00160                         goal.T1.point.x = north1;
00161                         goal.T1.point.y = east1;
00162                         goal.T1.point.z = 0;
00163                         goal.T2.point.x = north2;
00164                         goal.T2.point.y = east2;
00165                         goal.T2.point.z = 0;
00166                         goal.heading = heading;
00167                         goal.speed = speed;
00168                         goal.victory_radius = radius;
00169 
00170                         Go2Point.start(goal);
00171                 }
00172                 else
00173                 {
00174                         Go2Point.stop();
00175                 }
00176         }
00177 
00178         /*
00179          * Course keeping fully actuated primitive
00180          */
00181         void PrimitiveManager::go2point_FA(bool enable, double north1, double east1, double north2, double east2, double speed, double radius)
00182         {
00183                 typedef navcon_msgs::GoToPointGoal Goal;
00184                 if(enable)
00185                 {
00186                         Goal goal;
00187 
00188                         goal.ref_type = Goal::CONSTANT;
00189                         goal.subtype = Goal::GO2POINT_FA;
00190 
00191                         goal.T1.point.x = north1;
00192                         goal.T1.point.y = east1;
00193                         goal.T1.point.z = 0;
00194                         goal.T2.point.x = north2;
00195                         goal.T2.point.y = east2;
00196                         goal.T2.point.z = 0;
00197                         goal.heading = atan2(east2-east1,north2-north1);;
00198                         goal.speed = speed;
00199                         goal.victory_radius = radius;
00200 
00201 
00202                         LLcfg.LL_VELconfigure(true,2,2,0,0,0,2);
00203                         Go2Point.start(goal);
00204                 }
00205                 else
00206                 {
00207                         Go2Point.stop();
00208                         LLcfg.LL_VELconfigure(false,1,1,0,0,0,1);
00209 
00210                 }
00211         }
00212 
00213         /*
00214          * Course keeping underactuated primitive
00215          */
00216         void PrimitiveManager::go2point_UA(bool enable, double north1, double east1, double north2, double east2, double speed, double radius)
00217         {
00218                 typedef navcon_msgs::GoToPointGoal Goal;
00219                 if(enable)
00220                 {
00221                         Goal goal;
00222 
00223                         goal.ref_type = Goal::CONSTANT;
00224                         goal.subtype = Goal::GO2POINT_UA;
00225 
00226                         goal.T1.point.x = north1;
00227                         goal.T1.point.y = east1;
00228                         goal.T1.point.z = 0;
00229                         goal.T2.point.x = north2;
00230                         goal.T2.point.y = east2;
00231                         goal.T2.point.z = 0;
00232                         goal.heading = atan2(east2-east1,north2-north1);;
00233                         goal.speed = speed;
00234                         goal.victory_radius = radius;
00235 
00236                         Go2Point.start(goal);
00237                 }
00238                 else
00239                 {
00240                         Go2Point.stop();
00241                 }
00242         }
00243 
00244         void PrimitiveManager::dynamic_positioning(bool enable, double north, double east, double heading)
00245         {
00246                 typedef navcon_msgs::DynamicPositioningGoal Goal;
00247                 if(enable)
00248                 {
00249                         Goal goal;
00250 
00251                         //goal.ref_type = Goal::CONSTANT;
00252                         //goal.subtype = Goal::GO2POINT_UA;
00253 
00254                         goal.T1.point.x = north;
00255                         goal.T1.point.y = east;
00256                         goal.T1.point.z = 0;
00257                         goal.yaw = heading;
00258 
00259                         LLcfg.LL_VELconfigure(true,2,2,0,0,0,2);
00260                         DynamicPositioning.start(goal);
00261                 }
00262                 else
00263                 {
00264 
00265                         DynamicPositioning.stop();
00266                         LLcfg.LL_VELconfigure(false,2,2,0,0,0,2);
00267 
00268                 }
00269         }
00270 
00271         /*
00272          * Course keeping fully actuated primitive
00273          */
00274         void PrimitiveManager::course_keeping_FA(bool enable, double course, double speed, double heading)
00275         {
00276                 typedef navcon_msgs::CourseKeepingGoal Goal;
00277                 if(enable)
00278                 {
00279                         Goal goal;
00280 
00281                         goal.ref_type = Goal::CONSTANT;
00282                         goal.subtype = Goal::COURSE_KEEPING_FA;
00283 
00284                         goal.course = course;
00285                         goal.speed = speed;
00286                         goal.yaw = heading;
00287 
00288                         CourseKeeping.start(goal);
00289                 }
00290                 else
00291                 {
00292                         CourseKeeping.stop();
00293                 }
00294         }
00295 
00296         /*
00297          * Course keeping underactuated primitive
00298          */
00299         void PrimitiveManager::course_keeping_UA(bool enable, double course, double speed)
00300         {
00301                 typedef navcon_msgs::CourseKeepingGoal Goal;
00302                 if(enable)
00303                 {
00304                         Goal goal;
00305 
00306                         goal.ref_type = Goal::CONSTANT;
00307                         goal.subtype = Goal::COURSE_KEEPING_UA;
00308 
00309                         goal.course = course;
00310                         goal.speed = speed;
00311                         goal.yaw = 0;
00312 
00313                         CourseKeeping.start(goal);
00314                 }
00315                 else
00316                 {
00317                         CourseKeeping.stop();
00318                 }
00319         }
00320 
00321 //      void PrimitiveManager::ISOprimitive(bool enable, int dof, double command, double hysteresis, double reference, double sampling_rate){
00322 //
00323 //              if(enable){
00324 //
00325 //                      //self.velconName = rospy.get_param("~velcon_name","velcon")
00326 //                      //self.model_update = rospy.Publisher("model_update", ModelParamsUpdate)
00327 //                      ros::NodeHandle nh, ph("~");
00328 //                      string velconName;
00329 //                      ph.param<string>("velcon_name",velconName,"velcon");
00330 //
00331 //            const char *names[7] = {"Surge", "Sway", "Heave", "Roll", "Pitch", "Yaw", "Altitude"};
00332 //
00333 //                      /* configure velocity controller for identification */
00334 //                      int velcon[6] = {0,0,0,0,0,0};
00335 //                      if(dof == navcon_msgs::DOFIdentificationGoal::Altitude){
00336 //                              velcon[navcon_msgs::DOFIdentificationGoal::Heave] = 3;
00337 //                      } else {
00338 //                              velcon[dof] = 3;
00339 //                      }
00340 //
00341 //                      string tmp = velconName + "/" + names[dof] + "_ident_amplitude";
00342 //                      nh.setParam(tmp.c_str(), command);
00343 //                      tmp.assign(velconName + "/" + names[dof] + "_ident_hysteresis");
00344 //                      nh.setParam(tmp.c_str(), hysteresis);
00345 //                      tmp.assign(velconName + "/" + names[dof] + "_ident_ref");
00346 //                      nh.setParam(tmp.c_str(), reference);
00347 //
00348 //                      LLcfg.LL_VELconfigure(true,velcon[0], velcon[1], velcon[2], velcon[3], velcon[4], velcon[5]);
00349 //
00350 //                      //ROS_ERROR("DOF = %d, command = %f, hysteresis = %f, reference = %f, sampling_rate = %f", dof, command, hysteresis, reference, sampling_rate);
00351 //
00352 //                      navcon_msgs::DOFIdentificationGoal goal;
00353 //                      goal.command = command;
00354 //                      goal.dof = dof;
00355 //                      goal.hysteresis = hysteresis;
00356 //                      goal.reference = reference;
00357 //                      goal.sampling_rate = sampling_rate;
00358 //
00359 //                      DOFIdentification.start(goal);
00360 //
00361 //              } else {
00362 //
00363 //                      DOFIdentification.stop();
00364 //                      //LLcfg.LL_VELconfigure(false,1,1,0,0,0,1);
00365 //              }
00366 //
00367 //      }
00368 
00369 
00370 #endif /* PRIMITIVEMANAGER_HPP_ */


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