enum_to_string.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2016 Valdimir Ermakov
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <array>
18 #include <unordered_map>
19 #include <mavros/utils.h>
20 #include <ros/console.h>
21 
22 namespace mavros {
23 namespace utils {
24 using mavlink::minimal::MAV_AUTOPILOT;
25 using mavlink::minimal::MAV_TYPE;
26 using mavlink::minimal::MAV_STATE;
27 using mavlink::minimal::MAV_COMPONENT;
28 using mavlink::common::MAV_ESTIMATOR_TYPE;
29 using mavlink::common::ADSB_ALTITUDE_TYPE;
30 using mavlink::common::ADSB_EMITTER_TYPE;
31 using mavlink::common::GPS_FIX_TYPE;
32 using mavlink::common::MAV_MISSION_RESULT;
33 using mavlink::common::MAV_FRAME;
34 using mavlink::common::MAV_DISTANCE_SENSOR;
35 using mavlink::common::LANDING_TARGET_TYPE;
36 
37 // [[[cog:
38 // import pymavlink.dialects.v20.common as common
39 //
40 // def get_enum(ename):
41 // enum = sorted(common.enums[ename].items())
42 // enum.pop() # remove ENUM_END
43 // return enum
44 //
45 // def split_by(delim, s):
46 // for c in delim:
47 // if c in s:
48 // return s.split(c, 1)[0].strip()
49 //
50 // return s.strip()
51 //
52 // def make_whitespace(l, v):
53 // d = l - len(v)
54 // return ' ' * d if d > 0 else ' '
55 //
56 // def ename_array_name(ename, suffix=None):
57 // l = ename.rsplit('::', 1)
58 // return (l[1] if len(l) > 1 else l[0]).lower() + (suffix or '_strings')
59 //
60 // def array_outl(name, enum, suffix=None):
61 // array = ename_array_name(name, suffix)
62 // cog.outl(f"""\
63 // //! {name} values
64 // static const std::array<const std::string, {len(enum)}> {array}{{{{""")
65 //
66 // def to_string_outl(ename, funcname='to_string', suffix=None):
67 // array = ename_array_name(ename, suffix)
68 // cog.outl(f"""\
69 // std::string {funcname}({ename} e)
70 // {{
71 // size_t idx = enum_value(e);
72 // if (idx >= {array}.size())
73 // return std::to_string(idx);
74 //
75 // return {array}[idx];
76 // }}""")
77 //
78 // def enum_name_is_value_outl(ename, suffix=None, funcname='to_string'):
79 // enum = get_enum(ename)
80 //
81 // array_outl(ename, enum, suffix)
82 // for k, e in enum:
83 // name_short = e.name[len(ename) + 1:]
84 // sp = make_whitespace(30, name_short)
85 // if e.description:
86 // cog.outl(f"""/* {k:>2} */ "{name_short}",{sp}// {e.description}""")
87 // else:
88 // cog.outl(f"""/* {k:>2} */ "{name_short}",""")
89 //
90 // cog.outl("}};")
91 // cog.outl()
92 // to_string_outl(ename, funcname, suffix)
93 //
94 // ename = 'MAV_AUTOPILOT'
95 // enum = get_enum(ename)
96 //
97 // array_outl(ename, enum)
98 // for k, e in enum:
99 // value = split_by('-,/.', e.description)
100 // sp = make_whitespace(30, value)
101 // cog.outl(f"""/* {k:>2} */ "{value}",{sp}// {e.description}""")
102 //
103 // cog.outl("}};")
104 // cog.outl()
105 // to_string_outl(ename)
106 // ]]]
108 static const std::array<const std::string, 20> mav_autopilot_strings{{
109 /* 0 */ "Generic autopilot", // Generic autopilot, full support for everything
110 /* 1 */ "Reserved for future use", // Reserved for future use.
111 /* 2 */ "SLUGS autopilot", // SLUGS autopilot, http://slugsuav.soe.ucsc.edu
112 /* 3 */ "ArduPilot", // ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org
113 /* 4 */ "OpenPilot", // OpenPilot, http://openpilot.org
114 /* 5 */ "Generic autopilot only supporting simple waypoints", // Generic autopilot only supporting simple waypoints
115 /* 6 */ "Generic autopilot supporting waypoints and other simple navigation commands", // Generic autopilot supporting waypoints and other simple navigation commands
116 /* 7 */ "Generic autopilot supporting the full mission command set", // Generic autopilot supporting the full mission command set
117 /* 8 */ "No valid autopilot", // No valid autopilot, e.g. a GCS or other MAVLink component
118 /* 9 */ "PPZ UAV", // PPZ UAV - http://nongnu.org/paparazzi
119 /* 10 */ "UAV Dev Board", // UAV Dev Board
120 /* 11 */ "FlexiPilot", // FlexiPilot
121 /* 12 */ "PX4 Autopilot", // PX4 Autopilot - http://px4.io/
122 /* 13 */ "SMACCMPilot", // SMACCMPilot - http://smaccmpilot.org
123 /* 14 */ "AutoQuad", // AutoQuad -- http://autoquad.org
124 /* 15 */ "Armazila", // Armazila -- http://armazila.com
125 /* 16 */ "Aerob", // Aerob -- http://aerob.ru
126 /* 17 */ "ASLUAV autopilot", // ASLUAV autopilot -- http://www.asl.ethz.ch
127 /* 18 */ "SmartAP Autopilot", // SmartAP Autopilot - http://sky-drones.com
128 /* 19 */ "AirRails", // AirRails - http://uaventure.com
129 }};
130 
131 std::string to_string(MAV_AUTOPILOT e)
132 {
133  size_t idx = enum_value(e);
134  if (idx >= mav_autopilot_strings.size())
135  return std::to_string(idx);
136 
137  return mav_autopilot_strings[idx];
138 }
139 // [[[end]]] (checksum: c1feb82117da0447594aacbe5c52f97b)
140 
141 // [[[cog:
142 // ename = 'MAV_TYPE'
143 // enum = get_enum(ename)
144 //
145 // array_outl(ename, enum)
146 // for k, e in enum:
147 // value = split_by(',-/.', e.description)
148 // sp = make_whitespace(30, value)
149 // cog.outl(f"""/* {k:>2} */ "{value}",{sp}// {e.description}""")
150 //
151 // cog.outl("}};")
152 // cog.outl()
153 // to_string_outl(ename)
154 // ]]]
156 static const std::array<const std::string, 37> mav_type_strings{{
157 /* 0 */ "Generic micro air vehicle", // Generic micro air vehicle
158 /* 1 */ "Fixed wing aircraft", // Fixed wing aircraft.
159 /* 2 */ "Quadrotor", // Quadrotor
160 /* 3 */ "Coaxial helicopter", // Coaxial helicopter
161 /* 4 */ "Normal helicopter with tail rotor", // Normal helicopter with tail rotor.
162 /* 5 */ "Ground installation", // Ground installation
163 /* 6 */ "Operator control unit", // Operator control unit / ground control station
164 /* 7 */ "Airship", // Airship, controlled
165 /* 8 */ "Free balloon", // Free balloon, uncontrolled
166 /* 9 */ "Rocket", // Rocket
167 /* 10 */ "Ground rover", // Ground rover
168 /* 11 */ "Surface vessel", // Surface vessel, boat, ship
169 /* 12 */ "Submarine", // Submarine
170 /* 13 */ "Hexarotor", // Hexarotor
171 /* 14 */ "Octorotor", // Octorotor
172 /* 15 */ "Tricopter", // Tricopter
173 /* 16 */ "Flapping wing", // Flapping wing
174 /* 17 */ "Kite", // Kite
175 /* 18 */ "Onboard companion controller", // Onboard companion controller
176 /* 19 */ "Two", // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
177 /* 20 */ "Quad", // Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
178 /* 21 */ "Tiltrotor VTOL", // Tiltrotor VTOL
179 /* 22 */ "VTOL reserved 2", // VTOL reserved 2
180 /* 23 */ "VTOL reserved 3", // VTOL reserved 3
181 /* 24 */ "VTOL reserved 4", // VTOL reserved 4
182 /* 25 */ "VTOL reserved 5", // VTOL reserved 5
183 /* 26 */ "Gimbal", // Gimbal
184 /* 27 */ "ADSB system", // ADSB system
185 /* 28 */ "Steerable", // Steerable, nonrigid airfoil
186 /* 29 */ "Dodecarotor", // Dodecarotor
187 /* 30 */ "Camera", // Camera
188 /* 31 */ "Charging station", // Charging station
189 /* 32 */ "FLARM collision avoidance system", // FLARM collision avoidance system
190 /* 33 */ "Servo", // Servo
191 /* 34 */ "Open Drone ID. See https:", // Open Drone ID. See https://mavlink.io/en/services/opendroneid.html.
192 /* 35 */ "Decarotor", // Decarotor
193 /* 36 */ "Battery", // Battery
194 }};
195 
196 std::string to_string(MAV_TYPE e)
197 {
198  size_t idx = enum_value(e);
199  if (idx >= mav_type_strings.size())
200  return std::to_string(idx);
201 
202  return mav_type_strings[idx];
203 }
204 // [[[end]]] (checksum: 8fc2dcd1c935d5d338508685d9eac918)
205 
206 // [[[cog:
207 // ename = 'MAV_TYPE'
208 // enum_name_is_value_outl(ename, funcname='to_name', suffix='_names')
209 // ]]]
211 static const std::array<const std::string, 37> mav_type_names{{
212 /* 0 */ "GENERIC", // Generic micro air vehicle
213 /* 1 */ "FIXED_WING", // Fixed wing aircraft.
214 /* 2 */ "QUADROTOR", // Quadrotor
215 /* 3 */ "COAXIAL", // Coaxial helicopter
216 /* 4 */ "HELICOPTER", // Normal helicopter with tail rotor.
217 /* 5 */ "ANTENNA_TRACKER", // Ground installation
218 /* 6 */ "GCS", // Operator control unit / ground control station
219 /* 7 */ "AIRSHIP", // Airship, controlled
220 /* 8 */ "FREE_BALLOON", // Free balloon, uncontrolled
221 /* 9 */ "ROCKET", // Rocket
222 /* 10 */ "GROUND_ROVER", // Ground rover
223 /* 11 */ "SURFACE_BOAT", // Surface vessel, boat, ship
224 /* 12 */ "SUBMARINE", // Submarine
225 /* 13 */ "HEXAROTOR", // Hexarotor
226 /* 14 */ "OCTOROTOR", // Octorotor
227 /* 15 */ "TRICOPTER", // Tricopter
228 /* 16 */ "FLAPPING_WING", // Flapping wing
229 /* 17 */ "KITE", // Kite
230 /* 18 */ "ONBOARD_CONTROLLER", // Onboard companion controller
231 /* 19 */ "VTOL_DUOROTOR", // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
232 /* 20 */ "VTOL_QUADROTOR", // Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
233 /* 21 */ "VTOL_TILTROTOR", // Tiltrotor VTOL
234 /* 22 */ "VTOL_RESERVED2", // VTOL reserved 2
235 /* 23 */ "VTOL_RESERVED3", // VTOL reserved 3
236 /* 24 */ "VTOL_RESERVED4", // VTOL reserved 4
237 /* 25 */ "VTOL_RESERVED5", // VTOL reserved 5
238 /* 26 */ "GIMBAL", // Gimbal
239 /* 27 */ "ADSB", // ADSB system
240 /* 28 */ "PARAFOIL", // Steerable, nonrigid airfoil
241 /* 29 */ "DODECAROTOR", // Dodecarotor
242 /* 30 */ "CAMERA", // Camera
243 /* 31 */ "CHARGING_STATION", // Charging station
244 /* 32 */ "FLARM", // FLARM collision avoidance system
245 /* 33 */ "SERVO", // Servo
246 /* 34 */ "ODID", // Open Drone ID. See https://mavlink.io/en/services/opendroneid.html.
247 /* 35 */ "DECAROTOR", // Decarotor
248 /* 36 */ "BATTERY", // Battery
249 }};
250 
251 std::string to_name(MAV_TYPE e)
252 {
253  size_t idx = enum_value(e);
254  if (idx >= mav_type_names.size())
255  return std::to_string(idx);
256 
257  return mav_type_names[idx];
258 }
259 // [[[end]]] (checksum: 2d402cd11e54ad35405d53b7ab127e3d)
260 
261 // [[[cog:
262 // ename = 'MAV_STATE'
263 // enum = get_enum(ename)
264 //
265 // array_outl(ename, enum)
266 // for k, e in enum:
267 // value = e.name[len(ename) + 1:].title()
268 // sp = make_whitespace(30, value)
269 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
270 //
271 // cog.outl("}};")
272 // cog.outl()
273 // to_string_outl(ename)
274 // ]]]
276 static const std::array<const std::string, 9> mav_state_strings{{
277 /* 0 */ "Uninit", // Uninitialized system, state is unknown.
278 /* 1 */ "Boot", // System is booting up.
279 /* 2 */ "Calibrating", // System is calibrating and not flight-ready.
280 /* 3 */ "Standby", // System is grounded and on standby. It can be launched any time.
281 /* 4 */ "Active", // System is active and might be already airborne. Motors are engaged.
282 /* 5 */ "Critical", // System is in a non-normal flight mode. It can however still navigate.
283 /* 6 */ "Emergency", // System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.
284 /* 7 */ "Poweroff", // System just initialized its power-down sequence, will shut down now.
285 /* 8 */ "Flight_Termination", // System is terminating itself.
286 }};
287 
288 std::string to_string(MAV_STATE e)
289 {
290  size_t idx = enum_value(e);
291  if (idx >= mav_state_strings.size())
292  return std::to_string(idx);
293 
294  return mav_state_strings[idx];
295 }
296 // [[[end]]] (checksum: 8af1e6916d0229c193aab7d3dc2c97e9)
297 
298 // [[[cog:
299 // ename = "timesync_mode"
300 // ent = [ "NONE", "MAVLINK", "ONBOARD", "PASSTHROUGH", ]
301 //
302 // array_outl(ename, ent)
303 // for k, e in enumerate(ent):
304 // cog.outl("""/* {k:>2} */ "{e}",""".format(**locals()))
305 //
306 // cog.outl("}};")
307 // cog.outl()
308 // to_string_outl(ename)
309 // ]]]
311 static const std::array<const std::string, 4> timesync_mode_strings{{
312 /* 0 */ "NONE",
313 /* 1 */ "MAVLINK",
314 /* 2 */ "ONBOARD",
315 /* 3 */ "PASSTHROUGH",
316 }};
317 
318 std::string to_string(timesync_mode e)
319 {
320  size_t idx = enum_value(e);
321  if (idx >= timesync_mode_strings.size())
322  return std::to_string(idx);
323 
324  return timesync_mode_strings[idx];
325 }
326 // [[[end]]] (checksum: 2796eaa4f9361c2d7ca87f63e0401d4d)
327 
328 timesync_mode timesync_mode_from_str(const std::string &mode)
329 {
330  for (size_t idx = 0; idx < timesync_mode_strings.size(); idx++) {
331  if (timesync_mode_strings[idx] == mode) {
332  std::underlying_type<timesync_mode>::type rv = idx;
333  return static_cast<timesync_mode>(rv);
334  }
335  }
336 
337  ROS_ERROR_STREAM_NAMED("uas", "TM: Unknown mode: " << mode);
338  return timesync_mode::NONE;
339 }
340 
341 // [[[cog:
342 // ename = 'ADSB_ALTITUDE_TYPE'
343 // enum_name_is_value_outl(ename)
344 // ]]]
346 static const std::array<const std::string, 2> adsb_altitude_type_strings{{
347 /* 0 */ "PRESSURE_QNH", // Altitude reported from a Baro source using QNH reference
348 /* 1 */ "GEOMETRIC", // Altitude reported from a GNSS source
349 }};
350 
351 std::string to_string(ADSB_ALTITUDE_TYPE e)
352 {
353  size_t idx = enum_value(e);
354  if (idx >= adsb_altitude_type_strings.size())
355  return std::to_string(idx);
356 
357  return adsb_altitude_type_strings[idx];
358 }
359 // [[[end]]] (checksum: dc127bf29aefa513471d13c5a0e1e6ec)
360 
361 // [[[cog:
362 // ename = 'ADSB_EMITTER_TYPE'
363 // enum_name_is_value_outl(ename)
364 // ]]]
366 static const std::array<const std::string, 20> adsb_emitter_type_strings{{
367 /* 0 */ "NO_INFO",
368 /* 1 */ "LIGHT",
369 /* 2 */ "SMALL",
370 /* 3 */ "LARGE",
371 /* 4 */ "HIGH_VORTEX_LARGE",
372 /* 5 */ "HEAVY",
373 /* 6 */ "HIGHLY_MANUV",
374 /* 7 */ "ROTOCRAFT",
375 /* 8 */ "UNASSIGNED",
376 /* 9 */ "GLIDER",
377 /* 10 */ "LIGHTER_AIR",
378 /* 11 */ "PARACHUTE",
379 /* 12 */ "ULTRA_LIGHT",
380 /* 13 */ "UNASSIGNED2",
381 /* 14 */ "UAV",
382 /* 15 */ "SPACE",
383 /* 16 */ "UNASSGINED3",
384 /* 17 */ "EMERGENCY_SURFACE",
385 /* 18 */ "SERVICE_SURFACE",
386 /* 19 */ "POINT_OBSTACLE",
387 }};
388 
389 std::string to_string(ADSB_EMITTER_TYPE e)
390 {
391  size_t idx = enum_value(e);
392  if (idx >= adsb_emitter_type_strings.size())
393  return std::to_string(idx);
394 
395  return adsb_emitter_type_strings[idx];
396 }
397 // [[[end]]] (checksum: 713e0304603321e421131d8552d0f8e0)
398 
399 // [[[cog:
400 // ename = 'MAV_ESTIMATOR_TYPE'
401 // enum_name_is_value_outl(ename)
402 // ]]]
404 static const std::array<const std::string, 9> mav_estimator_type_strings{{
405 /* 0 */ "UNKNOWN", // Unknown type of the estimator.
406 /* 1 */ "NAIVE", // This is a naive estimator without any real covariance feedback.
407 /* 2 */ "VISION", // Computer vision based estimate. Might be up to scale.
408 /* 3 */ "VIO", // Visual-inertial estimate.
409 /* 4 */ "GPS", // Plain GPS estimate.
410 /* 5 */ "GPS_INS", // Estimator integrating GPS and inertial sensing.
411 /* 6 */ "MOCAP", // Estimate from external motion capturing system.
412 /* 7 */ "LIDAR", // Estimator based on lidar sensor input.
413 /* 8 */ "AUTOPILOT", // Estimator on autopilot.
414 }};
415 
416 std::string to_string(MAV_ESTIMATOR_TYPE e)
417 {
418  size_t idx = enum_value(e);
419  if (idx >= mav_estimator_type_strings.size())
420  return std::to_string(idx);
421 
422  return mav_estimator_type_strings[idx];
423 }
424 // [[[end]]] (checksum: 78a66e6898ff8c5dafb482dbf264a489)
425 
426 // [[[cog:
427 // ename = 'GPS_FIX_TYPE'
428 // enum_name_is_value_outl(ename)
429 // ]]]
431 static const std::array<const std::string, 9> gps_fix_type_strings{{
432 /* 0 */ "NO_GPS", // No GPS connected
433 /* 1 */ "NO_FIX", // No position information, GPS is connected
434 /* 2 */ "2D_FIX", // 2D position
435 /* 3 */ "3D_FIX", // 3D position
436 /* 4 */ "DGPS", // DGPS/SBAS aided 3D position
437 /* 5 */ "RTK_FLOAT", // RTK float, 3D position
438 /* 6 */ "RTK_FIXED", // RTK Fixed, 3D position
439 /* 7 */ "STATIC", // Static fixed, typically used for base stations
440 /* 8 */ "PPP", // PPP, 3D position.
441 }};
442 
443 std::string to_string(GPS_FIX_TYPE e)
444 {
445  size_t idx = enum_value(e);
446  if (idx >= gps_fix_type_strings.size())
447  return std::to_string(idx);
448 
449  return gps_fix_type_strings[idx];
450 }
451 // [[[end]]] (checksum: 7569b73b2d68ed1412bf0c36afeb131c)
452 
453 // [[[cog:
454 // ename = 'MAV_MISSION_RESULT'
455 // enum = get_enum(ename)
456 //
457 // array_outl(ename, enum)
458 // for k, e in enum:
459 // value = e.description
460 // sp = make_whitespace(30, value)
461 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
462 //
463 // cog.outl("}};")
464 // cog.outl()
465 // to_string_outl(ename)
466 // ]]]
468 static const std::array<const std::string, 16> mav_mission_result_strings{{
469 /* 0 */ "mission accepted OK", // mission accepted OK
470 /* 1 */ "Generic error / not accepting mission commands at all right now.", // Generic error / not accepting mission commands at all right now.
471 /* 2 */ "Coordinate frame is not supported.", // Coordinate frame is not supported.
472 /* 3 */ "Command is not supported.", // Command is not supported.
473 /* 4 */ "Mission items exceed storage space.", // Mission items exceed storage space.
474 /* 5 */ "One of the parameters has an invalid value.", // One of the parameters has an invalid value.
475 /* 6 */ "param1 has an invalid value.", // param1 has an invalid value.
476 /* 7 */ "param2 has an invalid value.", // param2 has an invalid value.
477 /* 8 */ "param3 has an invalid value.", // param3 has an invalid value.
478 /* 9 */ "param4 has an invalid value.", // param4 has an invalid value.
479 /* 10 */ "x / param5 has an invalid value.", // x / param5 has an invalid value.
480 /* 11 */ "y / param6 has an invalid value.", // y / param6 has an invalid value.
481 /* 12 */ "z / param7 has an invalid value.", // z / param7 has an invalid value.
482 /* 13 */ "Mission item received out of sequence", // Mission item received out of sequence
483 /* 14 */ "Not accepting any mission commands from this communication partner.", // Not accepting any mission commands from this communication partner.
484 /* 15 */ "Current mission operation cancelled (e.g. mission upload, mission download).", // Current mission operation cancelled (e.g. mission upload, mission download).
485 }};
486 
487 std::string to_string(MAV_MISSION_RESULT e)
488 {
489  size_t idx = enum_value(e);
490  if (idx >= mav_mission_result_strings.size())
491  return std::to_string(idx);
492 
493  return mav_mission_result_strings[idx];
494 }
495 // [[[end]]] (checksum: bf3c500065b1c65a1e822c70da56d2d5)
496 
497 // [[[cog:
498 // ename = 'MAV_FRAME'
499 // enum_name_is_value_outl(ename)
500 // ]]]
502 static const std::array<const std::string, 22> mav_frame_strings{{
503 /* 0 */ "GLOBAL", // Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
504 /* 1 */ "LOCAL_NED", // Local coordinate frame, Z-down (x: North, y: East, z: Down).
505 /* 2 */ "MISSION", // NOT a coordinate frame, indicates a mission command.
506 /* 3 */ "GLOBAL_RELATIVE_ALT", // Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
507 /* 4 */ "LOCAL_ENU", // Local coordinate frame, Z-up (x: East, y: North, z: Up).
508 /* 5 */ "GLOBAL_INT", // Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL).
509 /* 6 */ "GLOBAL_RELATIVE_ALT_INT", // Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.
510 /* 7 */ "LOCAL_OFFSET_NED", // Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
511 /* 8 */ "BODY_NED", // Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.
512 /* 9 */ "BODY_OFFSET_NED", // Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.
513 /* 10 */ "GLOBAL_TERRAIN_ALT", // Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
514 /* 11 */ "GLOBAL_TERRAIN_ALT_INT", // Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
515 /* 12 */ "BODY_FRD", // Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down).
516 /* 13 */ "RESERVED_13", // MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
517 /* 14 */ "RESERVED_14", // MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).
518 /* 15 */ "RESERVED_15", // MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).
519 /* 16 */ "RESERVED_16", // MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).
520 /* 17 */ "RESERVED_17", // MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up).
521 /* 18 */ "RESERVED_18", // MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down).
522 /* 19 */ "RESERVED_19", // MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up).
523 /* 20 */ "LOCAL_FRD", // Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame).
524 /* 21 */ "LOCAL_FLU", // Forward, Left, Up coordinate frame. This is a local frame with Z-up and arbitrary F/L alignment (i.e. not aligned with ENU/earth frame).
525 }};
526 
527 std::string to_string(MAV_FRAME e)
528 {
529  size_t idx = enum_value(e);
530  if (idx >= mav_frame_strings.size())
531  return std::to_string(idx);
532 
533  return mav_frame_strings[idx];
534 }
535 // [[[end]]] (checksum: f7783e4d7764c236021e92fc4a1c16a1)
536 
537 // [[[cog:
538 // ename = 'MAV_COMPONENT'
539 // suffix = 'MAV_COMP_ID'
540 // enum = get_enum(ename)
541 //
542 // cog.outl(f"static const std::unordered_map<size_t, const std::string> {suffix.lower()}_strings{{{{")
543 // for k, e in enum:
544 // name_short = e.name[len(suffix) + 1:]
545 // sp = make_whitespace(30, name_short)
546 // if e.description:
547 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},{sp}// {e.description}""")
548 // else:
549 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},""")
550 //
551 // cog.outl("}};")
552 // ]]]
553 static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
554 { 0, "ALL" }, // Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message.
555 { 1, "AUTOPILOT1" }, // System flight controller component ("autopilot"). Only one autopilot is expected in a particular system.
556 { 25, "USER1" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
557 { 26, "USER2" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
558 { 27, "USER3" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
559 { 28, "USER4" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
560 { 29, "USER5" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
561 { 30, "USER6" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
562 { 31, "USER7" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
563 { 32, "USER8" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
564 { 33, "USER9" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
565 { 34, "USER10" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
566 { 35, "USER11" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
567 { 36, "USER12" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
568 { 37, "USER13" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
569 { 38, "USER14" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
570 { 39, "USER15" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
571 { 40, "USER16" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
572 { 41, "USER17" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
573 { 42, "USER18" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
574 { 43, "USER19" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
575 { 44, "USER20" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
576 { 45, "USER21" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
577 { 46, "USER22" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
578 { 47, "USER23" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
579 { 48, "USER24" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
580 { 49, "USER25" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
581 { 50, "USER26" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
582 { 51, "USER27" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
583 { 52, "USER28" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
584 { 53, "USER29" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
585 { 54, "USER30" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
586 { 55, "USER31" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
587 { 56, "USER32" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
588 { 57, "USER33" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
589 { 58, "USER34" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
590 { 59, "USER35" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
591 { 60, "USER36" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
592 { 61, "USER37" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
593 { 62, "USER38" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
594 { 63, "USER39" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
595 { 64, "USER40" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
596 { 65, "USER41" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
597 { 66, "USER42" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
598 { 67, "USER43" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
599 { 68, "TELEMETRY_RADIO" }, // Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
600 { 69, "USER45" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
601 { 70, "USER46" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
602 { 71, "USER47" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
603 { 72, "USER48" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
604 { 73, "USER49" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
605 { 74, "USER50" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
606 { 75, "USER51" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
607 { 76, "USER52" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
608 { 77, "USER53" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
609 { 78, "USER54" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
610 { 79, "USER55" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
611 { 80, "USER56" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
612 { 81, "USER57" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
613 { 82, "USER58" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
614 { 83, "USER59" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
615 { 84, "USER60" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
616 { 85, "USER61" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
617 { 86, "USER62" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
618 { 87, "USER63" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
619 { 88, "USER64" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
620 { 89, "USER65" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
621 { 90, "USER66" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
622 { 91, "USER67" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
623 { 92, "USER68" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
624 { 93, "USER69" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
625 { 94, "USER70" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
626 { 95, "USER71" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
627 { 96, "USER72" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
628 { 97, "USER73" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
629 { 98, "USER74" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
630 { 99, "USER75" }, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
631 { 100, "CAMERA" }, // Camera #1.
632 { 101, "CAMERA2" }, // Camera #2.
633 { 102, "CAMERA3" }, // Camera #3.
634 { 103, "CAMERA4" }, // Camera #4.
635 { 104, "CAMERA5" }, // Camera #5.
636 { 105, "CAMERA6" }, // Camera #6.
637 { 140, "SERVO1" }, // Servo #1.
638 { 141, "SERVO2" }, // Servo #2.
639 { 142, "SERVO3" }, // Servo #3.
640 { 143, "SERVO4" }, // Servo #4.
641 { 144, "SERVO5" }, // Servo #5.
642 { 145, "SERVO6" }, // Servo #6.
643 { 146, "SERVO7" }, // Servo #7.
644 { 147, "SERVO8" }, // Servo #8.
645 { 148, "SERVO9" }, // Servo #9.
646 { 149, "SERVO10" }, // Servo #10.
647 { 150, "SERVO11" }, // Servo #11.
648 { 151, "SERVO12" }, // Servo #12.
649 { 152, "SERVO13" }, // Servo #13.
650 { 153, "SERVO14" }, // Servo #14.
651 { 154, "GIMBAL" }, // Gimbal #1.
652 { 155, "LOG" }, // Logging component.
653 { 156, "ADSB" }, // Automatic Dependent Surveillance-Broadcast (ADS-B) component.
654 { 157, "OSD" }, // On Screen Display (OSD) devices for video links.
655 { 158, "PERIPHERAL" }, // Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice.
656 { 159, "QX1_GIMBAL" }, // Gimbal ID for QX1.
657 { 160, "FLARM" }, // FLARM collision alert component.
658 { 171, "GIMBAL2" }, // Gimbal #2.
659 { 172, "GIMBAL3" }, // Gimbal #3.
660 { 173, "GIMBAL4" }, // Gimbal #4
661 { 174, "GIMBAL5" }, // Gimbal #5.
662 { 175, "GIMBAL6" }, // Gimbal #6.
663 { 180, "BATTERY" }, // Battery #1.
664 { 181, "BATTERY2" }, // Battery #2.
665 { 190, "MISSIONPLANNER" }, // Component that can generate/supply a mission flight plan (e.g. GCS or developer API).
666 { 191, "ONBOARD_COMPUTER" }, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
667 { 195, "PATHPLANNER" }, // Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
668 { 196, "OBSTACLE_AVOIDANCE" }, // Component that plans a collision free path between two points.
669 { 197, "VISUAL_INERTIAL_ODOMETRY" }, // Component that provides position estimates using VIO techniques.
670 { 198, "PAIRING_MANAGER" }, // Component that manages pairing of vehicle and GCS.
671 { 200, "IMU" }, // Inertial Measurement Unit (IMU) #1.
672 { 201, "IMU_2" }, // Inertial Measurement Unit (IMU) #2.
673 { 202, "IMU_3" }, // Inertial Measurement Unit (IMU) #3.
674 { 220, "GPS" }, // GPS #1.
675 { 221, "GPS2" }, // GPS #2.
676 { 236, "ODID_TXRX_1" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
677 { 237, "ODID_TXRX_2" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
678 { 238, "ODID_TXRX_3" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
679 { 240, "UDP_BRIDGE" }, // Component to bridge MAVLink to UDP (i.e. from a UART).
680 { 241, "UART_BRIDGE" }, // Component to bridge to UART (i.e. from UDP).
681 { 242, "TUNNEL_NODE" }, // Component handling TUNNEL messages (e.g. vendor specific GUI of a component).
682 { 250, "SYSTEM_CONTROL" }, // Component for handling system messages (e.g. to ARM, takeoff, etc.).
683 }};
684 // [[[end]]] (checksum: aa881c50ec1302df3d49fdc6fa6fe13a)
685 
686 std::string to_string(MAV_COMPONENT e)
687 {
688  size_t idx = enum_value(e);
689  auto it = mav_comp_id_strings.find(idx);
690 
691  if (it == mav_comp_id_strings.end())
692  return std::to_string(idx);
693 
694  return it->second;
695 }
696 
697 MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
698 {
699  for (size_t idx = 0; idx < mav_frame_strings.size(); idx++) {
700  if (mav_frame_strings[idx] == mav_frame) {
701  std::underlying_type<MAV_FRAME>::type rv = idx;
702  return static_cast<MAV_FRAME>(rv);
703  }
704  }
705 
706  ROS_ERROR_STREAM_NAMED("uas", "FRAME: Unknown MAV_FRAME: " << mav_frame);
707  return MAV_FRAME::LOCAL_NED;
708 }
709 
710 MAV_TYPE mav_type_from_str(const std::string &mav_type)
711 {
712  for (size_t idx = 0; idx < mav_type_names.size(); idx++) {
713  if (mav_type_names[idx] == mav_type) {
714  std::underlying_type<MAV_TYPE>::type rv = idx;
715  return static_cast<MAV_TYPE>(rv);
716  }
717  }
718  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown MAV_TYPE: " << mav_type);
719  return MAV_TYPE::GENERIC;
720 }
721 
722 // [[[cog:
723 // ename = 'MAV_DISTANCE_SENSOR'
724 // enum_name_is_value_outl(ename)
725 // ]]]
727 static const std::array<const std::string, 5> mav_distance_sensor_strings{{
728 /* 0 */ "LASER", // Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
729 /* 1 */ "ULTRASOUND", // Ultrasound rangefinder, e.g. MaxBotix units
730 /* 2 */ "INFRARED", // Infrared rangefinder, e.g. Sharp units
731 /* 3 */ "RADAR", // Radar type, e.g. uLanding units
732 /* 4 */ "UNKNOWN", // Broken or unknown type, e.g. analog units
733 }};
734 
735 std::string to_string(MAV_DISTANCE_SENSOR e)
736 {
737  size_t idx = enum_value(e);
738  if (idx >= mav_distance_sensor_strings.size())
739  return std::to_string(idx);
740 
741  return mav_distance_sensor_strings[idx];
742 }
743 // [[[end]]] (checksum: 3f792ad01cdb3f2315a8907f578ab5b3)
744 
745 // [[[cog:
746 // ename = 'LANDING_TARGET_TYPE'
747 // enum_name_is_value_outl(ename)
748 // ]]]
750 static const std::array<const std::string, 4> landing_target_type_strings{{
751 /* 0 */ "LIGHT_BEACON", // Landing target signaled by light beacon (ex: IR-LOCK)
752 /* 1 */ "RADIO_BEACON", // Landing target signaled by radio beacon (ex: ILS, NDB)
753 /* 2 */ "VISION_FIDUCIAL", // Landing target represented by a fiducial marker (ex: ARTag)
754 /* 3 */ "VISION_OTHER", // Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
755 }};
756 
757 std::string to_string(LANDING_TARGET_TYPE e)
758 {
759  size_t idx = enum_value(e);
760  if (idx >= landing_target_type_strings.size())
761  return std::to_string(idx);
762 
763  return landing_target_type_strings[idx];
764 }
765 // [[[end]]] (checksum: a42789c10cbebd5bc253abca2a07289b)
766 
767 LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
768 {
769  for (size_t idx = 0; idx < landing_target_type_strings.size(); idx++) {
770  if (landing_target_type_strings[idx] == landing_target_type) {
771  std::underlying_type<LANDING_TARGET_TYPE>::type rv = idx;
772  return static_cast<LANDING_TARGET_TYPE>(rv);
773  }
774  }
775  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown LANDING_TARGET_TYPE: " << landing_target_type << ". Defaulting to LIGHT_BEACON");
776  return LANDING_TARGET_TYPE::LIGHT_BEACON;
777 }
778 
779 } // namespace utils
780 } // namespace mavros
std::string to_name(MAV_TYPE e)
static const std::array< const std::string, 20 > mav_autopilot_strings
MAV_AUTOPILOT values.
static const std::array< const std::string, 4 > timesync_mode_strings
timesync_mode values
static const std::array< const std::string, 16 > mav_mission_result_strings
MAV_MISSION_RESULT values.
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
#define ROS_ERROR_STREAM_NAMED(name, args)
std::string to_string(LANDING_TARGET_TYPE e)
static const std::array< const std::string, 37 > mav_type_strings
MAV_TYPE values.
static const std::array< const std::string, 5 > mav_distance_sensor_strings
MAV_DISTANCE_SENSOR values.
static const std::array< const std::string, 37 > mav_type_names
MAV_TYPE values.
static const std::array< const std::string, 20 > adsb_emitter_type_strings
ADSB_EMITTER_TYPE values.
static const std::array< const std::string, 9 > mav_estimator_type_strings
MAV_ESTIMATOR_TYPE values.
static const std::array< const std::string, 2 > adsb_altitude_type_strings
ADSB_ALTITUDE_TYPE values.
mavlink::minimal::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
std::string to_string(timesync_mode e)
static const std::array< const std::string, 9 > gps_fix_type_strings
GPS_FIX_TYPE values.
static const std::array< const std::string, 22 > mav_frame_strings
MAV_FRAME values.
static const std::unordered_map< size_t, const std::string > mav_comp_id_strings
timesync_mode timesync_mode_from_str(const std::string &mode)
Retrieve timesync mode from name.
static const std::array< const std::string, 4 > landing_target_type_strings
LANDING_TARGET_TYPE values.
mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
Retrieve landing target type from alias name.
static const std::array< const std::string, 9 > mav_state_strings
MAV_STATE values.
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:26