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


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03