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, 36> 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 }};
194 
195 std::string to_string(MAV_TYPE e)
196 {
197  size_t idx = enum_value(e);
198  if (idx >= mav_type_strings.size())
199  return std::to_string(idx);
200 
201  return mav_type_strings[idx];
202 }
203 // [[[end]]] (checksum: f44b083f4b6be34f26d75692072f09bf)
204 
205 // [[[cog:
206 // ename = 'MAV_TYPE'
207 // enum_name_is_value_outl(ename, funcname='to_name', suffix='_names')
208 // ]]]
210 static const std::array<const std::string, 36> mav_type_names{{
211 /* 0 */ "GENERIC", // Generic micro air vehicle
212 /* 1 */ "FIXED_WING", // Fixed wing aircraft.
213 /* 2 */ "QUADROTOR", // Quadrotor
214 /* 3 */ "COAXIAL", // Coaxial helicopter
215 /* 4 */ "HELICOPTER", // Normal helicopter with tail rotor.
216 /* 5 */ "ANTENNA_TRACKER", // Ground installation
217 /* 6 */ "GCS", // Operator control unit / ground control station
218 /* 7 */ "AIRSHIP", // Airship, controlled
219 /* 8 */ "FREE_BALLOON", // Free balloon, uncontrolled
220 /* 9 */ "ROCKET", // Rocket
221 /* 10 */ "GROUND_ROVER", // Ground rover
222 /* 11 */ "SURFACE_BOAT", // Surface vessel, boat, ship
223 /* 12 */ "SUBMARINE", // Submarine
224 /* 13 */ "HEXAROTOR", // Hexarotor
225 /* 14 */ "OCTOROTOR", // Octorotor
226 /* 15 */ "TRICOPTER", // Tricopter
227 /* 16 */ "FLAPPING_WING", // Flapping wing
228 /* 17 */ "KITE", // Kite
229 /* 18 */ "ONBOARD_CONTROLLER", // Onboard companion controller
230 /* 19 */ "VTOL_DUOROTOR", // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
231 /* 20 */ "VTOL_QUADROTOR", // Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
232 /* 21 */ "VTOL_TILTROTOR", // Tiltrotor VTOL
233 /* 22 */ "VTOL_RESERVED2", // VTOL reserved 2
234 /* 23 */ "VTOL_RESERVED3", // VTOL reserved 3
235 /* 24 */ "VTOL_RESERVED4", // VTOL reserved 4
236 /* 25 */ "VTOL_RESERVED5", // VTOL reserved 5
237 /* 26 */ "GIMBAL", // Gimbal
238 /* 27 */ "ADSB", // ADSB system
239 /* 28 */ "PARAFOIL", // Steerable, nonrigid airfoil
240 /* 29 */ "DODECAROTOR", // Dodecarotor
241 /* 30 */ "CAMERA", // Camera
242 /* 31 */ "CHARGING_STATION", // Charging station
243 /* 32 */ "FLARM", // FLARM collision avoidance system
244 /* 33 */ "SERVO", // Servo
245 /* 34 */ "ODID", // Open Drone ID. See https://mavlink.io/en/services/opendroneid.html.
246 /* 35 */ "DECAROTOR", // Decarotor
247 }};
248 
249 std::string to_name(MAV_TYPE e)
250 {
251  size_t idx = enum_value(e);
252  if (idx >= mav_type_names.size())
253  return std::to_string(idx);
254 
255  return mav_type_names[idx];
256 }
257 // [[[end]]] (checksum: 3775b5a8763b4e66287a471af939ef6c)
258 
259 // [[[cog:
260 // ename = 'MAV_STATE'
261 // enum = get_enum(ename)
262 //
263 // array_outl(ename, enum)
264 // for k, e in enum:
265 // value = e.name[len(ename) + 1:].title()
266 // sp = make_whitespace(30, value)
267 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
268 //
269 // cog.outl("}};")
270 // cog.outl()
271 // to_string_outl(ename)
272 // ]]]
274 static const std::array<const std::string, 9> mav_state_strings{{
275 /* 0 */ "Uninit", // Uninitialized system, state is unknown.
276 /* 1 */ "Boot", // System is booting up.
277 /* 2 */ "Calibrating", // System is calibrating and not flight-ready.
278 /* 3 */ "Standby", // System is grounded and on standby. It can be launched any time.
279 /* 4 */ "Active", // System is active and might be already airborne. Motors are engaged.
280 /* 5 */ "Critical", // System is in a non-normal flight mode. It can however still navigate.
281 /* 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.
282 /* 7 */ "Poweroff", // System just initialized its power-down sequence, will shut down now.
283 /* 8 */ "Flight_Termination", // System is terminating itself.
284 }};
285 
286 std::string to_string(MAV_STATE e)
287 {
288  size_t idx = enum_value(e);
289  if (idx >= mav_state_strings.size())
290  return std::to_string(idx);
291 
292  return mav_state_strings[idx];
293 }
294 // [[[end]]] (checksum: 8af1e6916d0229c193aab7d3dc2c97e9)
295 
296 // [[[cog:
297 // ename = "timesync_mode"
298 // ent = [ "NONE", "MAVLINK", "ONBOARD", "PASSTHROUGH", ]
299 //
300 // array_outl(ename, ent)
301 // for k, e in enumerate(ent):
302 // cog.outl("""/* {k:>2} */ "{e}",""".format(**locals()))
303 //
304 // cog.outl("}};")
305 // cog.outl()
306 // to_string_outl(ename)
307 // ]]]
309 static const std::array<const std::string, 4> timesync_mode_strings{{
310 /* 0 */ "NONE",
311 /* 1 */ "MAVLINK",
312 /* 2 */ "ONBOARD",
313 /* 3 */ "PASSTHROUGH",
314 }};
315 
316 std::string to_string(timesync_mode e)
317 {
318  size_t idx = enum_value(e);
319  if (idx >= timesync_mode_strings.size())
320  return std::to_string(idx);
321 
322  return timesync_mode_strings[idx];
323 }
324 // [[[end]]] (checksum: 2796eaa4f9361c2d7ca87f63e0401d4d)
325 
326 timesync_mode timesync_mode_from_str(const std::string &mode)
327 {
328  for (size_t idx = 0; idx < timesync_mode_strings.size(); idx++) {
329  if (timesync_mode_strings[idx] == mode) {
330  std::underlying_type<timesync_mode>::type rv = idx;
331  return static_cast<timesync_mode>(rv);
332  }
333  }
334 
335  ROS_ERROR_STREAM_NAMED("uas", "TM: Unknown mode: " << mode);
336  return timesync_mode::NONE;
337 }
338 
339 // [[[cog:
340 // ename = 'ADSB_ALTITUDE_TYPE'
341 // enum_name_is_value_outl(ename)
342 // ]]]
344 static const std::array<const std::string, 2> adsb_altitude_type_strings{{
345 /* 0 */ "PRESSURE_QNH", // Altitude reported from a Baro source using QNH reference
346 /* 1 */ "GEOMETRIC", // Altitude reported from a GNSS source
347 }};
348 
349 std::string to_string(ADSB_ALTITUDE_TYPE e)
350 {
351  size_t idx = enum_value(e);
352  if (idx >= adsb_altitude_type_strings.size())
353  return std::to_string(idx);
354 
355  return adsb_altitude_type_strings[idx];
356 }
357 // [[[end]]] (checksum: dc127bf29aefa513471d13c5a0e1e6ec)
358 
359 // [[[cog:
360 // ename = 'ADSB_EMITTER_TYPE'
361 // enum_name_is_value_outl(ename)
362 // ]]]
364 static const std::array<const std::string, 20> adsb_emitter_type_strings{{
365 /* 0 */ "NO_INFO",
366 /* 1 */ "LIGHT",
367 /* 2 */ "SMALL",
368 /* 3 */ "LARGE",
369 /* 4 */ "HIGH_VORTEX_LARGE",
370 /* 5 */ "HEAVY",
371 /* 6 */ "HIGHLY_MANUV",
372 /* 7 */ "ROTOCRAFT",
373 /* 8 */ "UNASSIGNED",
374 /* 9 */ "GLIDER",
375 /* 10 */ "LIGHTER_AIR",
376 /* 11 */ "PARACHUTE",
377 /* 12 */ "ULTRA_LIGHT",
378 /* 13 */ "UNASSIGNED2",
379 /* 14 */ "UAV",
380 /* 15 */ "SPACE",
381 /* 16 */ "UNASSGINED3",
382 /* 17 */ "EMERGENCY_SURFACE",
383 /* 18 */ "SERVICE_SURFACE",
384 /* 19 */ "POINT_OBSTACLE",
385 }};
386 
387 std::string to_string(ADSB_EMITTER_TYPE e)
388 {
389  size_t idx = enum_value(e);
390  if (idx >= adsb_emitter_type_strings.size())
391  return std::to_string(idx);
392 
393  return adsb_emitter_type_strings[idx];
394 }
395 // [[[end]]] (checksum: 713e0304603321e421131d8552d0f8e0)
396 
397 // [[[cog:
398 // ename = 'MAV_ESTIMATOR_TYPE'
399 // enum_name_is_value_outl(ename)
400 // ]]]
402 static const std::array<const std::string, 9> mav_estimator_type_strings{{
403 /* 0 */ "UNKNOWN", // Unknown type of the estimator.
404 /* 1 */ "NAIVE", // This is a naive estimator without any real covariance feedback.
405 /* 2 */ "VISION", // Computer vision based estimate. Might be up to scale.
406 /* 3 */ "VIO", // Visual-inertial estimate.
407 /* 4 */ "GPS", // Plain GPS estimate.
408 /* 5 */ "GPS_INS", // Estimator integrating GPS and inertial sensing.
409 /* 6 */ "MOCAP", // Estimate from external motion capturing system.
410 /* 7 */ "LIDAR", // Estimator based on lidar sensor input.
411 /* 8 */ "AUTOPILOT", // Estimator on autopilot.
412 }};
413 
414 std::string to_string(MAV_ESTIMATOR_TYPE e)
415 {
416  size_t idx = enum_value(e);
417  if (idx >= mav_estimator_type_strings.size())
418  return std::to_string(idx);
419 
420  return mav_estimator_type_strings[idx];
421 }
422 // [[[end]]] (checksum: 78a66e6898ff8c5dafb482dbf264a489)
423 
424 // [[[cog:
425 // ename = 'GPS_FIX_TYPE'
426 // enum_name_is_value_outl(ename)
427 // ]]]
429 static const std::array<const std::string, 9> gps_fix_type_strings{{
430 /* 0 */ "NO_GPS", // No GPS connected
431 /* 1 */ "NO_FIX", // No position information, GPS is connected
432 /* 2 */ "2D_FIX", // 2D position
433 /* 3 */ "3D_FIX", // 3D position
434 /* 4 */ "DGPS", // DGPS/SBAS aided 3D position
435 /* 5 */ "RTK_FLOAT", // RTK float, 3D position
436 /* 6 */ "RTK_FIXED", // RTK Fixed, 3D position
437 /* 7 */ "STATIC", // Static fixed, typically used for base stations
438 /* 8 */ "PPP", // PPP, 3D position.
439 }};
440 
441 std::string to_string(GPS_FIX_TYPE e)
442 {
443  size_t idx = enum_value(e);
444  if (idx >= gps_fix_type_strings.size())
445  return std::to_string(idx);
446 
447  return gps_fix_type_strings[idx];
448 }
449 // [[[end]]] (checksum: 7569b73b2d68ed1412bf0c36afeb131c)
450 
451 // [[[cog:
452 // ename = 'MAV_MISSION_RESULT'
453 // enum = get_enum(ename)
454 //
455 // array_outl(ename, enum)
456 // for k, e in enum:
457 // value = e.description
458 // sp = make_whitespace(30, value)
459 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
460 //
461 // cog.outl("}};")
462 // cog.outl()
463 // to_string_outl(ename)
464 // ]]]
466 static const std::array<const std::string, 16> mav_mission_result_strings{{
467 /* 0 */ "mission accepted OK", // mission accepted OK
468 /* 1 */ "Generic error / not accepting mission commands at all right now.", // Generic error / not accepting mission commands at all right now.
469 /* 2 */ "Coordinate frame is not supported.", // Coordinate frame is not supported.
470 /* 3 */ "Command is not supported.", // Command is not supported.
471 /* 4 */ "Mission items exceed storage space.", // Mission items exceed storage space.
472 /* 5 */ "One of the parameters has an invalid value.", // One of the parameters has an invalid value.
473 /* 6 */ "param1 has an invalid value.", // param1 has an invalid value.
474 /* 7 */ "param2 has an invalid value.", // param2 has an invalid value.
475 /* 8 */ "param3 has an invalid value.", // param3 has an invalid value.
476 /* 9 */ "param4 has an invalid value.", // param4 has an invalid value.
477 /* 10 */ "x / param5 has an invalid value.", // x / param5 has an invalid value.
478 /* 11 */ "y / param6 has an invalid value.", // y / param6 has an invalid value.
479 /* 12 */ "z / param7 has an invalid value.", // z / param7 has an invalid value.
480 /* 13 */ "Mission item received out of sequence", // Mission item received out of sequence
481 /* 14 */ "Not accepting any mission commands from this communication partner.", // Not accepting any mission commands from this communication partner.
482 /* 15 */ "Current mission operation cancelled (e.g. mission upload, mission download).", // Current mission operation cancelled (e.g. mission upload, mission download).
483 }};
484 
485 std::string to_string(MAV_MISSION_RESULT e)
486 {
487  size_t idx = enum_value(e);
488  if (idx >= mav_mission_result_strings.size())
489  return std::to_string(idx);
490 
491  return mav_mission_result_strings[idx];
492 }
493 // [[[end]]] (checksum: bf3c500065b1c65a1e822c70da56d2d5)
494 
495 // [[[cog:
496 // ename = 'MAV_FRAME'
497 // enum_name_is_value_outl(ename)
498 // ]]]
500 static const std::array<const std::string, 22> mav_frame_strings{{
501 /* 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).
502 /* 1 */ "LOCAL_NED", // Local coordinate frame, Z-down (x: North, y: East, z: Down).
503 /* 2 */ "MISSION", // NOT a coordinate frame, indicates a mission command.
504 /* 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.
505 /* 4 */ "LOCAL_ENU", // Local coordinate frame, Z-up (x: East, y: North, z: Up).
506 /* 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).
507 /* 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.
508 /* 7 */ "LOCAL_OFFSET_NED", // Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
509 /* 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.
510 /* 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.
511 /* 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.
512 /* 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.
513 /* 12 */ "BODY_FRD", // Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down).
514 /* 13 */ "RESERVED_13", // MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
515 /* 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).
516 /* 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).
517 /* 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).
518 /* 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).
519 /* 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).
520 /* 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).
521 /* 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).
522 /* 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).
523 }};
524 
525 std::string to_string(MAV_FRAME e)
526 {
527  size_t idx = enum_value(e);
528  if (idx >= mav_frame_strings.size())
529  return std::to_string(idx);
530 
531  return mav_frame_strings[idx];
532 }
533 // [[[end]]] (checksum: f7783e4d7764c236021e92fc4a1c16a1)
534 
535 // [[[cog:
536 // ename = 'MAV_COMPONENT'
537 // suffix = 'MAV_COMP_ID'
538 // enum = get_enum(ename)
539 //
540 // cog.outl(f"static const std::unordered_map<typename std::underlying_type<{ename}>::type, const std::string> {suffix.lower()}_strings{{{{")
541 // for k, e in enum:
542 // name_short = e.name[len(suffix) + 1:]
543 // sp = make_whitespace(30, name_short)
544 // if e.description:
545 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},{sp}// {e.description}""")
546 // else:
547 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},""")
548 //
549 // cog.outl("}};")
550 // ]]]
551 static const std::unordered_map<typename std::underlying_type<MAV_COMPONENT>::type, const std::string> mav_comp_id_strings{{
552 { 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.
553 { 1, "AUTOPILOT1" }, // System flight controller component ("autopilot"). Only one autopilot is expected in a particular system.
554 { 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.
555 { 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.
556 { 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.
557 { 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.
558 { 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.
559 { 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.
560 { 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.
561 { 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.
562 { 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.
563 { 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.
564 { 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.
565 { 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.
566 { 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.
567 { 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.
568 { 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.
569 { 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.
570 { 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.
571 { 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.
572 { 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.
573 { 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.
574 { 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.
575 { 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.
576 { 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.
577 { 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.
578 { 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.
579 { 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.
580 { 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.
581 { 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.
582 { 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.
583 { 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.
584 { 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.
585 { 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.
586 { 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.
587 { 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.
588 { 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.
589 { 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.
590 { 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.
591 { 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.
592 { 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.
593 { 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.
594 { 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.
595 { 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.
596 { 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.
597 { 68, "TELEMETRY_RADIO" }, // Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
598 { 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.
599 { 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.
600 { 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.
601 { 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.
602 { 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.
603 { 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.
604 { 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.
605 { 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.
606 { 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.
607 { 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.
608 { 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.
609 { 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.
610 { 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.
611 { 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.
612 { 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.
613 { 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.
614 { 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.
615 { 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.
616 { 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.
617 { 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.
618 { 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.
619 { 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.
620 { 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.
621 { 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.
622 { 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.
623 { 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.
624 { 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.
625 { 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.
626 { 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.
627 { 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.
628 { 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.
629 { 100, "CAMERA" }, // Camera #1.
630 { 101, "CAMERA2" }, // Camera #2.
631 { 102, "CAMERA3" }, // Camera #3.
632 { 103, "CAMERA4" }, // Camera #4.
633 { 104, "CAMERA5" }, // Camera #5.
634 { 105, "CAMERA6" }, // Camera #6.
635 { 140, "SERVO1" }, // Servo #1.
636 { 141, "SERVO2" }, // Servo #2.
637 { 142, "SERVO3" }, // Servo #3.
638 { 143, "SERVO4" }, // Servo #4.
639 { 144, "SERVO5" }, // Servo #5.
640 { 145, "SERVO6" }, // Servo #6.
641 { 146, "SERVO7" }, // Servo #7.
642 { 147, "SERVO8" }, // Servo #8.
643 { 148, "SERVO9" }, // Servo #9.
644 { 149, "SERVO10" }, // Servo #10.
645 { 150, "SERVO11" }, // Servo #11.
646 { 151, "SERVO12" }, // Servo #12.
647 { 152, "SERVO13" }, // Servo #13.
648 { 153, "SERVO14" }, // Servo #14.
649 { 154, "GIMBAL" }, // Gimbal #1.
650 { 155, "LOG" }, // Logging component.
651 { 156, "ADSB" }, // Automatic Dependent Surveillance-Broadcast (ADS-B) component.
652 { 157, "OSD" }, // On Screen Display (OSD) devices for video links.
653 { 158, "PERIPHERAL" }, // Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice.
654 { 159, "QX1_GIMBAL" }, // Gimbal ID for QX1.
655 { 160, "FLARM" }, // FLARM collision alert component.
656 { 171, "GIMBAL2" }, // Gimbal #2.
657 { 172, "GIMBAL3" }, // Gimbal #3.
658 { 173, "GIMBAL4" }, // Gimbal #4
659 { 174, "GIMBAL5" }, // Gimbal #5.
660 { 175, "GIMBAL6" }, // Gimbal #6.
661 { 190, "MISSIONPLANNER" }, // Component that can generate/supply a mission flight plan (e.g. GCS or developer API).
662 { 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.
663 { 195, "PATHPLANNER" }, // Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
664 { 196, "OBSTACLE_AVOIDANCE" }, // Component that plans a collision free path between two points.
665 { 197, "VISUAL_INERTIAL_ODOMETRY" }, // Component that provides position estimates using VIO techniques.
666 { 198, "PAIRING_MANAGER" }, // Component that manages pairing of vehicle and GCS.
667 { 200, "IMU" }, // Inertial Measurement Unit (IMU) #1.
668 { 201, "IMU_2" }, // Inertial Measurement Unit (IMU) #2.
669 { 202, "IMU_3" }, // Inertial Measurement Unit (IMU) #3.
670 { 220, "GPS" }, // GPS #1.
671 { 221, "GPS2" }, // GPS #2.
672 { 236, "ODID_TXRX_1" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
673 { 237, "ODID_TXRX_2" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
674 { 238, "ODID_TXRX_3" }, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
675 { 240, "UDP_BRIDGE" }, // Component to bridge MAVLink to UDP (i.e. from a UART).
676 { 241, "UART_BRIDGE" }, // Component to bridge to UART (i.e. from UDP).
677 { 242, "TUNNEL_NODE" }, // Component handling TUNNEL messages (e.g. vendor specific GUI of a component).
678 { 250, "SYSTEM_CONTROL" }, // Component for handling system messages (e.g. to ARM, takeoff, etc.).
679 }};
680 // [[[end]]] (checksum: 2dc119e3e20f7668a71e8649ba3f67b6)
681 
682 std::string to_string(MAV_COMPONENT e)
683 {
684  auto idx = enum_value(e);
685  auto it = mav_comp_id_strings.find(idx);
686 
687  if (it == mav_comp_id_strings.end())
688  return std::to_string(idx);
689 
690  return it->second;
691 }
692 
693 MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
694 {
695  for (size_t idx = 0; idx < mav_frame_strings.size(); idx++) {
696  if (mav_frame_strings[idx] == mav_frame) {
697  std::underlying_type<MAV_FRAME>::type rv = idx;
698  return static_cast<MAV_FRAME>(rv);
699  }
700  }
701 
702  ROS_ERROR_STREAM_NAMED("uas", "FRAME: Unknown MAV_FRAME: " << mav_frame);
703  return MAV_FRAME::LOCAL_NED;
704 }
705 
706 MAV_TYPE mav_type_from_str(const std::string &mav_type)
707 {
708  for (size_t idx = 0; idx < mav_type_names.size(); idx++) {
709  if (mav_type_names[idx] == mav_type) {
710  std::underlying_type<MAV_TYPE>::type rv = idx;
711  return static_cast<MAV_TYPE>(rv);
712  }
713  }
714  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown MAV_TYPE: " << mav_type);
715  return MAV_TYPE::GENERIC;
716 }
717 
718 // [[[cog:
719 // ename = 'MAV_DISTANCE_SENSOR'
720 // enum_name_is_value_outl(ename)
721 // ]]]
723 static const std::array<const std::string, 5> mav_distance_sensor_strings{{
724 /* 0 */ "LASER", // Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
725 /* 1 */ "ULTRASOUND", // Ultrasound rangefinder, e.g. MaxBotix units
726 /* 2 */ "INFRARED", // Infrared rangefinder, e.g. Sharp units
727 /* 3 */ "RADAR", // Radar type, e.g. uLanding units
728 /* 4 */ "UNKNOWN", // Broken or unknown type, e.g. analog units
729 }};
730 
731 std::string to_string(MAV_DISTANCE_SENSOR e)
732 {
733  size_t idx = enum_value(e);
734  if (idx >= mav_distance_sensor_strings.size())
735  return std::to_string(idx);
736 
737  return mav_distance_sensor_strings[idx];
738 }
739 // [[[end]]] (checksum: 3f792ad01cdb3f2315a8907f578ab5b3)
740 
741 // [[[cog:
742 // ename = 'LANDING_TARGET_TYPE'
743 // enum_name_is_value_outl(ename)
744 // ]]]
746 static const std::array<const std::string, 4> landing_target_type_strings{{
747 /* 0 */ "LIGHT_BEACON", // Landing target signaled by light beacon (ex: IR-LOCK)
748 /* 1 */ "RADIO_BEACON", // Landing target signaled by radio beacon (ex: ILS, NDB)
749 /* 2 */ "VISION_FIDUCIAL", // Landing target represented by a fiducial marker (ex: ARTag)
750 /* 3 */ "VISION_OTHER", // Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
751 }};
752 
753 std::string to_string(LANDING_TARGET_TYPE e)
754 {
755  size_t idx = enum_value(e);
756  if (idx >= landing_target_type_strings.size())
757  return std::to_string(idx);
758 
759  return landing_target_type_strings[idx];
760 }
761 // [[[end]]] (checksum: a42789c10cbebd5bc253abca2a07289b)
762 
763 LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
764 {
765  for (size_t idx = 0; idx < landing_target_type_strings.size(); idx++) {
766  if (landing_target_type_strings[idx] == landing_target_type) {
767  std::underlying_type<LANDING_TARGET_TYPE>::type rv = idx;
768  return static_cast<LANDING_TARGET_TYPE>(rv);
769  }
770  }
771  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown LANDING_TARGET_TYPE: " << landing_target_type << ". Defaulting to LIGHT_BEACON");
772  return LANDING_TARGET_TYPE::LIGHT_BEACON;
773 }
774 
775 } // namespace utils
776 } // 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, 36 > mav_type_strings
MAV_TYPE 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, 5 > mav_distance_sensor_strings
MAV_DISTANCE_SENSOR 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.
static const std::array< const std::string, 36 > mav_type_names
MAV_TYPE values.
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< typename std::underlying_type< MAV_COMPONENT >::type, 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 13 2023 02:17:50