uas.cpp
Go to the documentation of this file.
00001 
00006 /*
00007  * Copyright 2014 Vladimir Ermakov.
00008  *
00009  * This program is free software; you can redistribute it and/or modify
00010  * it under the terms of the GNU General Public License as published by
00011  * the Free Software Foundation; either version 3 of the License, or
00012  * (at your option) any later version.
00013  *
00014  * This program is distributed in the hope that it will be useful, but
00015  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
00016  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
00017  * for more details.
00018  *
00019  * You should have received a copy of the GNU General Public License along
00020  * with this program; if not, write to the Free Software Foundation, Inc.,
00021  * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
00022  */
00023 
00024 #include <stdexcept>
00025 #include <mavros/mavros_uas.h>
00026 #include <mavros/utils.h>
00027 #include <mavros/px4_custom_mode.h>
00028 
00029 using namespace mavros;
00030 
00031 UAS::UAS() :
00032         type(MAV_TYPE_GENERIC),
00033         autopilot(MAV_AUTOPILOT_GENERIC),
00034         target_system(1),
00035         target_component(1),
00036         connected(false),
00037         angular_velocity(),
00038         linear_acceleration(),
00039         orientation(),
00040         gps_latitude(0),
00041         gps_longitude(0),
00042         gps_altitude(0),
00043         gps_eph(0),
00044         gps_epv(0),
00045         fix_status(0)
00046 {
00047 }
00048 
00049 void UAS::stop(void)
00050 {
00051 }
00052 
00053 /* -*- mode stringify functions -*- */
00054 
00055 typedef std::map<uint32_t, std::string> cmode_map;
00056 
00058 static const cmode_map arduplane_cmode_map = {
00059         { 0, "MANUAL" },
00060         { 1, "CIRCLE" },
00061         { 2, "STABILIZE" },
00062         { 3, "TRAINING" },
00063         { 4, "ACRO" },
00064         { 5, "FBWA" },
00065         { 6, "FBWB" },
00066         { 7, "CRUISE" },
00067         { 8, "AUTOTUNE" },
00068         { 10, "AUTO" },
00069         { 11, "RTL" },
00070         { 12, "LOITER" },
00071         { 14, "LAND" },
00072         { 15, "GUIDED" },
00073         { 16, "INITIALISING" }
00074 };
00075 
00077 static const cmode_map arducopter_cmode_map = {
00078         { 0, "STABILIZE" },
00079         { 1, "ACRO" },
00080         { 2, "ALT_HOLD" },
00081         { 3, "AUTO" },
00082         { 4, "GUIDED" },
00083         { 5, "LOITER" },
00084         { 6, "RTL" },
00085         { 7, "CIRCLE" },
00086         { 8, "POSITION" },
00087         { 9, "LAND" },
00088         { 10, "OF_LOITER" },
00089         { 11, "APPROACH" }
00090 };
00091 
00093 static const cmode_map px4_cmode_map = {
00094         { px4::define_mode(px4::custom_mode::MAIN_MODE_MANUAL),           "MANUAL" },
00095         { px4::define_mode(px4::custom_mode::MAIN_MODE_ACRO),             "ACRO" },
00096         { px4::define_mode(px4::custom_mode::MAIN_MODE_ALTCTL),           "ALTCTL" },
00097         { px4::define_mode(px4::custom_mode::MAIN_MODE_POSCTL),           "POSCTL" },
00098         { px4::define_mode(px4::custom_mode::MAIN_MODE_OFFBOARD),         "OFFBOARD" },
00099         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_MISSION), "AUTO.MISSION" },
00100         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_LOITER),  "AUTO.LOITER" },
00101         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_RTL),     "AUTO.RTL" },
00102         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_LAND),    "AUTO.LAND" },
00103         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_RTGS),    "AUTO.RTGS" },
00104         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_READY),   "AUTO.READY" },
00105         { px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_TAKEOFF), "AUTO.TAKEOFF" }
00106 };
00107 
00108 static inline std::string str_base_mode(int base_mode) {
00109         std::ostringstream mode;
00110         mode << "MODE(0x" << std::hex << std::uppercase << base_mode << ")";
00111         return mode.str();
00112 }
00113 
00114 static std::string str_custom_mode(uint32_t custom_mode) {
00115         std::ostringstream mode;
00116         mode << "CMODE(" << custom_mode << ")";
00117         return mode.str();
00118 }
00119 
00120 static std::string str_mode_cmap(const cmode_map &cmap, uint32_t custom_mode) {
00121         auto it = cmap.find(custom_mode);
00122         if (it != cmap.end())
00123                 return it->second;
00124         else
00125                 return str_custom_mode(custom_mode);
00126 }
00127 
00128 static inline std::string str_mode_px4(uint32_t custom_mode_int) {
00129         px4::custom_mode custom_mode(custom_mode_int);
00130 
00131         // clear fields
00132         custom_mode.reserved = 0;
00133         if (custom_mode.main_mode != px4::custom_mode::MAIN_MODE_AUTO) {
00134                 ROS_WARN_COND_NAMED(custom_mode.sub_mode != 0, "uas", "PX4: Unknown sub-mode");
00135                 custom_mode.sub_mode = 0;
00136         }
00137 
00138         return str_mode_cmap(px4_cmode_map, custom_mode.data);
00139 }
00140 
00141 static inline bool is_apm_copter(enum MAV_TYPE &type) {
00142         return type == MAV_TYPE_QUADROTOR ||
00143                 type == MAV_TYPE_HEXAROTOR ||
00144                 type == MAV_TYPE_OCTOROTOR ||
00145                 type == MAV_TYPE_TRICOPTER ||
00146                 type == MAV_TYPE_COAXIAL;
00147 }
00148 
00149 std::string UAS::str_mode_v10(uint8_t base_mode, uint32_t custom_mode) {
00150         if (!(base_mode && MAV_MODE_FLAG_CUSTOM_MODE_ENABLED))
00151                 return str_base_mode(base_mode);
00152 
00153         auto type = get_type();
00154         auto ap = get_autopilot();
00155         if (MAV_AUTOPILOT_ARDUPILOTMEGA == ap) {
00156                 if (is_apm_copter(type))
00157                         return str_mode_cmap(arducopter_cmode_map, custom_mode);
00158                 else if (type == MAV_TYPE_FIXED_WING)
00159                         return str_mode_cmap(arduplane_cmode_map, custom_mode);
00160                 else
00161                         /* TODO: APM:Rover */
00162                         return str_custom_mode(custom_mode);
00163         }
00164         else if (MAV_AUTOPILOT_PX4 == ap)
00165                 return str_mode_px4(custom_mode);
00166         else
00167                 /* TODO: other autopilot */
00168                 return str_custom_mode(custom_mode);
00169 }
00170 
00171 static bool cmode_find_cmap(const cmode_map &cmap, std::string &cmode_str, uint32_t &cmode) {
00172         // 1. try find by name
00173         for (auto &mode : cmap) {
00174                 if (mode.second == cmode_str) {
00175                         cmode = mode.first;
00176                         return true;
00177                 }
00178         }
00179 
00180         // 2. try convert integer
00182         try {
00183                 cmode = std::stoi(cmode_str, 0, 0);
00184                 return true;
00185         }
00186         catch (std::invalid_argument &ex) {
00187                 // failed
00188         }
00189 
00190         // Debugging output.
00191         std::ostringstream os;
00192         for (auto &mode : cmap)
00193                 os << " " << mode.second;
00194 
00195         ROS_ERROR_STREAM_NAMED("uas", "MODE: Unknown mode: " << cmode_str);
00196         ROS_DEBUG_STREAM_NAMED("uas", "MODE: Known modes are:" << os.str());
00197 
00198         return false;
00199 }
00200 
00201 bool UAS::cmode_from_str(std::string cmode_str, uint32_t &custom_mode) {
00202         // upper case
00203         std::transform(cmode_str.begin(), cmode_str.end(), cmode_str.begin(), std::ref(toupper));
00204 
00205         auto type = get_type();
00206         auto ap = get_autopilot();
00207         if (MAV_AUTOPILOT_ARDUPILOTMEGA == ap) {
00208                 if (is_apm_copter(type))
00209                         return cmode_find_cmap(arducopter_cmode_map, cmode_str, custom_mode);
00210                 else if (type == MAV_TYPE_FIXED_WING)
00211                         return cmode_find_cmap(arduplane_cmode_map, cmode_str, custom_mode);
00212         }
00213         else if (MAV_AUTOPILOT_PX4 == ap)
00214                 return cmode_find_cmap(px4_cmode_map, cmode_str, custom_mode);
00215 
00216         ROS_ERROR_NAMED("uas", "MODE: Unsupported FCU");
00217         return false;
00218 }


mavros
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:13