MAV'RIC
|
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 mavlink_waypoint_handler.hpp 00034 * 00035 * \author MAV'RIC Team 00036 * \author Nicolas Dousse 00037 * \author Matthew Douglas 00038 * 00039 * \brief The MAVLink waypoint handler 00040 * 00041 ******************************************************************************/ 00042 00043 00044 #ifndef MAVLINK_WAYPOINT_HANDLER__ 00045 #define MAVLINK_WAYPOINT_HANDLER__ 00046 00047 #include "communication/mavlink_message_handler.hpp" 00048 #include "communication/mavlink_stream.hpp" 00049 #include "communication/mavlink_message_handler.hpp" 00050 #include "mission/mission_handler_registry.hpp" 00051 #include "mission/waypoint.hpp" 00052 #include "sensing/ins.hpp" 00053 00054 #define MAX_WAYPOINTS 10 ///< The maximal size of the waypoint list 00055 00056 /* 00057 * N.B.: Reference Frames and MAV_CMD_NAV are defined in "maveric.h" 00058 */ 00059 00060 class Mavlink_waypoint_handler 00061 { 00062 public: 00063 00064 struct conf_t 00065 { 00066 float home_altitude; 00067 }; 00068 00069 00081 Mavlink_waypoint_handler( const INS& ins, 00082 Mavlink_message_handler& message_handler, 00083 const Mavlink_stream& mavlink_stream, 00084 Mission_handler_registry& mission_handler_registry, 00085 conf_t config = default_config()); 00086 00087 bool init(); 00088 00094 inline uint16_t waypoint_count() const {return waypoint_count_;}; 00095 00101 inline uint64_t waypoint_received_time_ms() const { return waypoint_received_time_ms_; }; 00102 00108 static inline conf_t default_config(); 00109 00118 const Waypoint& current_waypoint() const; 00119 00128 const Waypoint& next_waypoint() const; 00129 00138 const Waypoint& waypoint_from_index(int i) const; 00139 00149 const Waypoint& home_waypoint() const; 00150 00155 void advance_to_next_waypoint(); 00156 00162 uint16_t current_waypoint_index() const; 00163 00171 bool set_current_waypoint_index(int index); 00172 00173 protected: 00174 Waypoint waypoint_list_[MAX_WAYPOINTS]; 00175 uint16_t waypoint_count_; 00176 uint16_t current_waypoint_index_; 00177 00178 Waypoint home_waypoint_; 00179 00180 const Mavlink_stream& mavlink_stream_; 00181 const INS& ins_; 00182 Mavlink_message_handler& message_handler_; 00183 Mission_handler_registry& mission_handler_registry_; 00184 private: 00185 uint64_t waypoint_received_time_ms_; 00186 00187 uint16_t requested_waypoint_count_; 00188 00189 uint32_t timeout_max_waypoint_; 00190 00191 conf_t config_; 00192 00196 void send_home_waypoint(); 00197 00198 /************************************************ 00199 * static member functions (callbacks) * 00200 ************************************************/ 00201 00210 static mav_result_t set_home(Mavlink_waypoint_handler* waypoint_handler, const mavlink_command_long_t* packet); 00211 00219 static void request_list_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00220 00228 static void mission_request_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00229 00237 static void mission_ack_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00238 00246 static void mission_count_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00247 00255 static void mission_item_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00256 00264 static void mission_clear_all_callback(Mavlink_waypoint_handler* waypoint_handler, uint32_t sysid, const mavlink_message_t* msg); 00265 }; 00266 00267 00268 Mavlink_waypoint_handler::conf_t Mavlink_waypoint_handler::default_config() 00269 { 00270 conf_t conf = {}; 00271 00272 conf.home_altitude = -10.0f; 00273 00274 return conf; 00275 }; 00276 00277 00278 00279 00280 00281 00282 00283 #endif // MAVLINK_WAYPOINT_HANDLER__