uas_stringify.cpp
Go to the documentation of this file.
1 
6 /*
7  * Copyright 2014 Vladimir Ermakov.
8  *
9  * This file is part of the mavros package and subject to the license terms
10  * in the top-level LICENSE file of the mavros repository.
11  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
12  */
13 
14 #include <array>
15 #include <unordered_map>
16 #include <stdexcept>
17 #include <mavros/mavros_uas.h>
18 #include <mavros/px4_custom_mode.h>
19 
20 using namespace mavros;
22 
23 
24 /* -*- mode stringify functions -*- */
25 
26 typedef std::unordered_map<uint32_t, const std::string> cmode_map;
27 
33  { 0, "MANUAL" },
34  { 1, "CIRCLE" },
35  { 2, "STABILIZE" },
36  { 3, "TRAINING" },
37  { 4, "ACRO" },
38  { 5, "FBWA" },
39  { 6, "FBWB" },
40  { 7, "CRUISE" },
41  { 8, "AUTOTUNE" },
42  { 10, "AUTO" },
43  { 11, "RTL" },
44  { 12, "LOITER" },
45  { 14, "LAND" }, // not in list
46  { 15, "GUIDED" },
47  { 16, "INITIALISING" },
48  { 17, "QSTABILIZE" }, // QuadPlane
49  { 18, "QHOVER" },
50  { 19, "QLOITER" },
51  { 20, "QLAND" },
52  { 21, "QRTL" }
53 }};
54 
60  { 0, "STABILIZE" },
61  { 1, "ACRO" },
62  { 2, "ALT_HOLD" },
63  { 3, "AUTO" },
64  { 4, "GUIDED" },
65  { 5, "LOITER" },
66  { 6, "RTL" },
67  { 7, "CIRCLE" },
68  { 8, "POSITION" }, // not in list
69  { 9, "LAND" },
70  { 10, "OF_LOITER" },
71  { 11, "DRIFT" }, // renamed, prev name: APPROACH
72  { 13, "SPORT" },
73  { 14, "FLIP" },
74  { 15, "AUTOTUNE" },
75  { 16, "POSHOLD" },
76  { 17, "BRAKE" },
77  { 18, "THROW" },
78  { 19, "AVOID_ADSB" },
79  { 20, "GUIDED_NOGPS" }
80 }};
81 
87  { 0, "MANUAL" },
88  { 2, "LEARNING" },
89  { 3, "STEERING" },
90  { 4, "HOLD" },
91  { 10, "AUTO" },
92  { 11, "RTL" },
93  { 15, "GUIDED" },
94  { 16, "INITIALISING" }
95 }};
96 
104  { 0, "STABILIZE" },
105  { 1, "ACRO" },
106  { 2, "ALT_HOLD" },
107  { 3, "AUTO" }, // n/a
108  { 4, "GUIDED" }, // n/a
109  { 5, "VELHOLD" },
110  { 6, "RTL" }, // n/a
111  { 7, "CIRCLE" }, // n/a
112  { 9, "SURFACE" },
113  { 10, "OF_LOITER" }, // deprecated
114  { 11, "DRIFT" }, // n/a
115  { 13, "TRANSECT" },
116  { 14, "FLIP" }, // n/a
117  { 15, "AUTOTUNE" }, // n/a
118  { 16, "POSHOLD" },
119  { 17, "BRAKE" }, // n/a
120  { 18, "THROW" },
121  { 19, "MANUAL" }
122 }};
123 
125 static const cmode_map px4_cmode_map{{
142 }};
143 
144 static inline std::string str_base_mode(int base_mode) {
145  return utils::format("MODE(0x%2X)", base_mode);
146 }
147 
148 static std::string str_custom_mode(uint32_t custom_mode) {
149  return utils::format("CMODE(%u)", custom_mode);
150 }
151 
152 static std::string str_mode_cmap(const cmode_map &cmap, uint32_t custom_mode)
153 {
154  auto it = cmap.find(custom_mode);
155  if (it != cmap.end())
156  return it->second;
157  else
158  return str_custom_mode(custom_mode);
159 }
160 
161 static inline std::string str_mode_px4(uint32_t custom_mode_int)
162 {
163  px4::custom_mode custom_mode(custom_mode_int);
164 
165  // clear fields
166  custom_mode.reserved = 0;
167  if (custom_mode.main_mode != px4::custom_mode::MAIN_MODE_AUTO) {
168  ROS_WARN_COND_NAMED(custom_mode.sub_mode != 0, "uas", "PX4: Unknown sub-mode %d.%d",
169  custom_mode.main_mode, custom_mode.sub_mode);
170  custom_mode.sub_mode = 0;
171  }
172 
173  return str_mode_cmap(px4_cmode_map, custom_mode.data);
174 }
175 
176 static inline bool is_apm_copter(UAS::MAV_TYPE type)
177 {
178  return type == UAS::MAV_TYPE::QUADROTOR ||
179  type == UAS::MAV_TYPE::HEXAROTOR ||
180  type == UAS::MAV_TYPE::OCTOROTOR ||
181  type == UAS::MAV_TYPE::TRICOPTER ||
182  type == UAS::MAV_TYPE::COAXIAL;
183 }
184 
185 std::string UAS::str_mode_v10(uint8_t base_mode, uint32_t custom_mode)
186 {
187  if (!(base_mode & enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED)))
188  return str_base_mode(base_mode);
189 
190  auto type = get_type();
191  auto ap = get_autopilot();
192  if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
193  if (is_apm_copter(type))
194  return str_mode_cmap(arducopter_cmode_map, custom_mode);
195  else if (type == MAV_TYPE::FIXED_WING)
196  return str_mode_cmap(arduplane_cmode_map, custom_mode);
197  else if (type == MAV_TYPE::GROUND_ROVER)
198  return str_mode_cmap(apmrover2_cmode_map, custom_mode);
199  else if (type == MAV_TYPE::SURFACE_BOAT)
200  return str_mode_cmap(apmrover2_cmode_map, custom_mode); // NOTE: #1051 for now (19.06.2018) boat is same as rover
201  else if (type == MAV_TYPE::SUBMARINE)
202  return str_mode_cmap(ardusub_cmode_map, custom_mode);
203  else {
204  ROS_WARN_THROTTLE_NAMED(30, "uas", "MODE: Unknown APM based FCU! Type: %d", enum_value(type));
205  return str_custom_mode(custom_mode);
206  }
207  }
208  else if (MAV_AUTOPILOT::PX4 == ap)
209  return str_mode_px4(custom_mode);
210  else
211  /* TODO: other autopilot */
212  return str_custom_mode(custom_mode);
213 }
214 
215 /* XXX TODO
216  * Add a fallback CMODE(dec) decoder for unknown FCU's
217  */
218 
219 static bool cmode_find_cmap(const cmode_map &cmap, std::string &cmode_str, uint32_t &cmode)
220 {
221  // 1. try find by name
222  for (auto &mode : cmap) {
223  if (mode.second == cmode_str) {
224  cmode = mode.first;
225  return true;
226  }
227  }
228 
229  // 2. try convert integer
231  try {
232  cmode = std::stoi(cmode_str, 0, 0);
233  return true;
234  }
235  catch (std::invalid_argument &ex) {
236  // failed
237  }
238 
239  // Debugging output.
240  std::ostringstream os;
241  for (auto &mode : cmap)
242  os << " " << mode.second;
243 
244  ROS_ERROR_STREAM_NAMED("uas", "MODE: Unknown mode: " << cmode_str);
245  ROS_INFO_STREAM_NAMED("uas", "MODE: Known modes are:" << os.str());
246 
247  return false;
248 }
249 
250 bool UAS::cmode_from_str(std::string cmode_str, uint32_t &custom_mode)
251 {
252  // upper case
253  std::transform(cmode_str.begin(), cmode_str.end(), cmode_str.begin(), std::ref(toupper));
254 
255  auto type = get_type();
256  auto ap = get_autopilot();
257  if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
258  if (is_apm_copter(type))
259  return cmode_find_cmap(arducopter_cmode_map, cmode_str, custom_mode);
260  else if (type == MAV_TYPE::FIXED_WING)
261  return cmode_find_cmap(arduplane_cmode_map, cmode_str, custom_mode);
262  else if (type == MAV_TYPE::GROUND_ROVER)
263  return cmode_find_cmap(apmrover2_cmode_map, cmode_str, custom_mode);
264  else if (type == MAV_TYPE::SUBMARINE)
265  return cmode_find_cmap(ardusub_cmode_map, cmode_str, custom_mode);
266  }
267  else if (MAV_AUTOPILOT::PX4 == ap)
268  return cmode_find_cmap(px4_cmode_map, cmode_str, custom_mode);
269 
270  ROS_ERROR_NAMED("uas", "MODE: Unsupported FCU");
271  return false;
272 }
static std::string str_base_mode(int base_mode)
#define ROS_WARN_COND_NAMED(cond, name,...)
bool cmode_from_str(std::string cmode_str, uint32_t &custom_mode)
Lookup custom mode for given string.
std::string format(const std::string &fmt, Args...args)
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
#define ROS_ERROR_STREAM_NAMED(name, args)
static const cmode_map apmrover2_cmode_map
MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
Definition: mavros_uas.h:127
static std::string str_mode_px4(uint32_t custom_mode_int)
static bool is_apm_copter(UAS::MAV_TYPE type)
mavlink::common::MAV_TYPE MAV_TYPE
Definition: mavros_uas.h:73
#define ROS_INFO_STREAM_NAMED(name, args)
static std::string str_custom_mode(uint32_t custom_mode)
static bool cmode_find_cmap(const cmode_map &cmap, std::string &cmode_str, uint32_t &cmode)
static const cmode_map ardusub_cmode_map
constexpr uint32_t define_mode_auto(enum custom_mode::SUB_MODE_AUTO sm)
helper function to define auto mode as uint32_t constant
std::atomic< uint8_t > type
Definition: mavros_uas.h:400
std::string str_mode_v10(uint8_t base_mode, uint32_t custom_mode)
Represent FCU mode as string.
static const cmode_map arduplane_cmode_map
static std::string str_mode_cmap(const cmode_map &cmap, uint32_t custom_mode)
PX4 custom mode.
MAVROS Plugin context.
MAV_TYPE get_type()
Returns vehicle type.
Definition: mavros_uas.h:119
static const cmode_map arducopter_cmode_map
PX4 custom mode constantsPX4 custom flight modes.
#define ROS_ERROR_NAMED(name,...)
constexpr uint32_t define_mode(enum custom_mode::MAIN_MODE mm, uint8_t sm=0)
helper function to define any mode as uint32_t constant
std::unordered_map< uint32_t, const std::string > cmode_map
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
static const cmode_map px4_cmode_map
PX4 custom mode -> string.


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11