MAV'RIC
/home/travis/build/lis-epfl/MAVRIC_Library/mission/mission_planner.hpp
00001 /*******************************************************************************
00002  * Copyright (c) 2009-2016, MAV'RIC Development Team
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  * 1. Redistributions of source code must retain the above copyright notice,
00009  * this list of conditions and the following disclaimer.
00010  *
00011  * 2. Redistributions in binary form must reproduce the above copyright notice,
00012  * this list of conditions and the following disclaimer in the documentation
00013  * and/or other materials provided with the distribution.
00014  *
00015  * 3. Neither the name of the copyright holder nor the names of its contributors
00016  * may be used to endorse or promote products derived from this software without
00017  * specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  ******************************************************************************/
00031 
00032 /*******************************************************************************
00033  * \file mission_planner.hpp
00034  *
00035  * \author MAV'RIC Team
00036  * \author Matthew Douglas
00037  * \author Julien Lecoeur
00038  *
00039  * \brief The mission planner
00040  *
00041  ******************************************************************************/
00042 
00043 
00044 #ifndef MISSION_PLANNER_HPP_
00045 #define MISSION_PLANNER_HPP_
00046 
00047 #include "communication/mavlink_communication.hpp"
00048 #include "communication/mavlink_stream.hpp"
00049 #include "communication/mavlink_waypoint_handler.hpp"
00050 #include "sensing/ahrs.hpp"
00051 #include "sensing/ins.hpp"
00052 #include "communication/mavlink_message_handler.hpp"
00053 #include "status/state.hpp"
00054 #include "manual_control/manual_control.hpp"
00055 #include "status/geofence.hpp"
00056 #include "mission/mission_handler_registry.hpp"
00057 #include "navigation/dubin.hpp"
00058 #include "flight_controller/flight_controller.hpp"
00059 
00060 class Mission_handler;
00061 
00062 /*
00063  * N.B.: Reference Frames and MAV_CMD_NAV are defined in "maveric.h"
00064  */
00065 
00066 class Mission_planner: public Flight_command_source
00067 {
00068 public:
00069     enum internal_state_t
00070     {
00071         STANDBY,
00072         PREMISSION,
00073         MISSION,
00074         POSTMISSION,
00075         PAUSED,
00076         MANUAL_CTRL
00077     };
00078 
00082     enum critical_behavior_enum
00083     {
00084         CLIMB_TO_SAFE_ALT,                                  
00085         FLY_TO_HOME_WP,                                     
00086         HOME_LAND,                                          
00087         CRITICAL_LAND                                       
00088     };
00089 
00090     struct conf_t
00091     {
00092         float safe_altitude;                                
00093         float critical_landing_altitude;                    
00094         float takeoff_altitude;                             
00095     };
00096 
00097 
00113     Mission_planner(    INS& ins,
00114                         const AHRS& ahrs,
00115                         State& state,
00116                         const Manual_control& manual_control,
00117                         const Geofence& geofence,
00118                         Mavlink_message_handler& message_handler,
00119                         const Mavlink_stream& mavlink_stream,
00120                         Mavlink_waypoint_handler& waypoint_handler,
00121                         Mission_handler_registry& mission_handler_registry,
00122                         conf_t config = default_config());
00123 
00124 
00125     bool init();
00126 
00127 
00133     static bool update(Mission_planner* mission_planner);
00134 
00135 
00141     bool write_flight_command(Flight_controller& flight_controller) const;
00142 
00143 
00149     static inline conf_t default_config();
00150 
00151 
00152     void set_critical_next_state(bool critical_next_state);
00153 
00154 
00160     internal_state_t internal_state() const;
00161 
00167     critical_behavior_enum critical_behavior() const;
00168 
00181     bool switch_mission_handler(const Waypoint& waypoint);
00182 
00195     bool insert_ad_hoc_waypoint(Waypoint wpt);
00196 
00202     inline float& takeoff_altitude() { return config_.takeoff_altitude; }
00203 
00204 protected:
00205     Mission_handler* current_mission_handler_;                  
00206     Waypoint inserted_waypoint_;                                
00207 
00208     internal_state_t internal_state_;                           
00209     critical_behavior_enum critical_behavior_;                   
00210 
00211     Mavlink_waypoint_handler& waypoint_handler_;                
00212     Mission_handler_registry& mission_handler_registry_;        
00213 
00214     bool require_takeoff_;                                      
00215     bool hold_position_set_;                                    
00216 
00217     bool critical_next_state_;                                  
00218     Waypoint critical_waypoint_;                                
00219 
00220     const Mavlink_stream& mavlink_stream_;                      
00221     State& state_;                                              
00222     INS& ins_;                                                  
00223     const AHRS& ahrs_;                                          
00224     const Manual_control& manual_control_;                      
00225     const Geofence& geofence_;                                  
00226     Mavlink_message_handler& message_handler_;                  
00227 
00228     conf_t config_;
00229 
00230 
00231 
00236     void state_machine();
00237 
00242     void critical_handler();
00243 
00253     void set_internal_state(internal_state_t new_internal_state);
00254 
00255     /************************************************
00256      *      static member functions (callbacks)     *
00257      ************************************************/
00258 
00265     bool set_current_waypoint(uint16_t index);
00266 
00267 
00276     static void mission_set_current_callback(Mission_planner* mission_planner, uint32_t sysid, const mavlink_message_t* msg);
00277 
00288     static mav_result_t nav_go_home(Mission_planner* mission_planner, const mavlink_command_long_t* packet);
00289 
00298     static mav_result_t mission_start_callback(Mission_planner* mission_planner, const mavlink_command_long_t* packet);
00299 
00300 
00309     static mav_result_t nav_takeoff_callback(Mission_planner* mission_planner, const mavlink_command_long_t* packet);
00310 
00319     static mav_result_t nav_land_callback(Mission_planner* mission_planner, const mavlink_command_long_t* packet);
00320 
00329     static mav_result_t override_goto_callback(Mission_planner* mission_planner, const mavlink_command_long_t* packet);
00330 };
00331 
00332 
00333 Mission_planner::conf_t Mission_planner::default_config()
00334 {
00335     conf_t conf                                                 = {};
00336 
00337     conf.safe_altitude                                          = -30.0f;
00338     conf.critical_landing_altitude                              =  -5.0f;
00339     conf.takeoff_altitude                                       = -10.0f;
00340 
00341     return conf;
00342 };
00343 
00344 
00345 
00346 
00347 
00348 
00349 
00350 #endif // MISSION_PLANNER_HPP_
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines