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::common::MAV_AUTOPILOT;
25 using mavlink::common::MAV_TYPE;
26 using mavlink::common::MAV_STATE;
27 using mavlink::common::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, http://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: 4b5a1e0cd8f9d21b956818e7efa3bc2e)
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, 33> 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 */ "Onboard gimbal", // Onboard gimbal
184 /* 27 */ "Onboard ADSB peripheral", // Onboard ADSB peripheral
185 /* 28 */ "Steerable", // Steerable, nonrigid airfoil
186 /* 29 */ "Dodecarotor", // Dodecarotor
187 /* 30 */ "Camera", // Camera
188 /* 31 */ "Charging station", // Charging station
189 /* 32 */ "Onboard FLARM collision avoidance system", // Onboard FLARM collision avoidance system
190 }};
191 
192 std::string to_string(MAV_TYPE e)
193 {
194  size_t idx = enum_value(e);
195  if (idx >= mav_type_strings.size())
196  return std::to_string(idx);
197 
198  return mav_type_strings[idx];
199 }
200 // [[[end]]] (checksum: 31488f5970b0f82b3efef71e32590bb6)
201 
202 // [[[cog:
203 // ename = 'MAV_TYPE'
204 // enum_name_is_value_outl(ename, funcname='to_name', suffix='_names')
205 // ]]]
207 static const std::array<const std::string, 33> mav_type_names{{
208 /* 0 */ "GENERIC", // Generic micro air vehicle.
209 /* 1 */ "FIXED_WING", // Fixed wing aircraft.
210 /* 2 */ "QUADROTOR", // Quadrotor
211 /* 3 */ "COAXIAL", // Coaxial helicopter
212 /* 4 */ "HELICOPTER", // Normal helicopter with tail rotor.
213 /* 5 */ "ANTENNA_TRACKER", // Ground installation
214 /* 6 */ "GCS", // Operator control unit / ground control station
215 /* 7 */ "AIRSHIP", // Airship, controlled
216 /* 8 */ "FREE_BALLOON", // Free balloon, uncontrolled
217 /* 9 */ "ROCKET", // Rocket
218 /* 10 */ "GROUND_ROVER", // Ground rover
219 /* 11 */ "SURFACE_BOAT", // Surface vessel, boat, ship
220 /* 12 */ "SUBMARINE", // Submarine
221 /* 13 */ "HEXAROTOR", // Hexarotor
222 /* 14 */ "OCTOROTOR", // Octorotor
223 /* 15 */ "TRICOPTER", // Tricopter
224 /* 16 */ "FLAPPING_WING", // Flapping wing
225 /* 17 */ "KITE", // Kite
226 /* 18 */ "ONBOARD_CONTROLLER", // Onboard companion controller
227 /* 19 */ "VTOL_DUOROTOR", // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
228 /* 20 */ "VTOL_QUADROTOR", // Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
229 /* 21 */ "VTOL_TILTROTOR", // Tiltrotor VTOL
230 /* 22 */ "VTOL_RESERVED2", // VTOL reserved 2
231 /* 23 */ "VTOL_RESERVED3", // VTOL reserved 3
232 /* 24 */ "VTOL_RESERVED4", // VTOL reserved 4
233 /* 25 */ "VTOL_RESERVED5", // VTOL reserved 5
234 /* 26 */ "GIMBAL", // Onboard gimbal
235 /* 27 */ "ADSB", // Onboard ADSB peripheral
236 /* 28 */ "PARAFOIL", // Steerable, nonrigid airfoil
237 /* 29 */ "DODECAROTOR", // Dodecarotor
238 /* 30 */ "CAMERA", // Camera
239 /* 31 */ "CHARGING_STATION", // Charging station
240 /* 32 */ "FLARM", // Onboard FLARM collision avoidance system
241 }};
242 
243 std::string to_name(MAV_TYPE e)
244 {
245  size_t idx = enum_value(e);
246  if (idx >= mav_type_names.size())
247  return std::to_string(idx);
248 
249  return mav_type_names[idx];
250 }
251 // [[[end]]] (checksum: ef412b11a1d1d703f7e2a2244693543f)
252 
253 // [[[cog:
254 // ename = 'MAV_STATE'
255 // enum = get_enum(ename)
256 //
257 // array_outl(ename, enum)
258 // for k, e in enum:
259 // value = e.name[len(ename) + 1:].title()
260 // sp = make_whitespace(30, value)
261 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
262 //
263 // cog.outl("}};")
264 // cog.outl()
265 // to_string_outl(ename)
266 // ]]]
268 static const std::array<const std::string, 9> mav_state_strings{{
269 /* 0 */ "Uninit", // Uninitialized system, state is unknown.
270 /* 1 */ "Boot", // System is booting up.
271 /* 2 */ "Calibrating", // System is calibrating and not flight-ready.
272 /* 3 */ "Standby", // System is grounded and on standby. It can be launched any time.
273 /* 4 */ "Active", // System is active and might be already airborne. Motors are engaged.
274 /* 5 */ "Critical", // System is in a non-normal flight mode. It can however still navigate.
275 /* 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.
276 /* 7 */ "Poweroff", // System just initialized its power-down sequence, will shut down now.
277 /* 8 */ "Flight_Termination", // System is terminating itself.
278 }};
279 
280 std::string to_string(MAV_STATE e)
281 {
282  size_t idx = enum_value(e);
283  if (idx >= mav_state_strings.size())
284  return std::to_string(idx);
285 
286  return mav_state_strings[idx];
287 }
288 // [[[end]]] (checksum: 8af1e6916d0229c193aab7d3dc2c97e9)
289 
290 // [[[cog:
291 // ename = "timesync_mode"
292 // ent = [ "NONE", "MAVLINK", "ONBOARD", "PASSTHROUGH", ]
293 //
294 // array_outl(ename, ent)
295 // for k, e in enumerate(ent):
296 // cog.outl("""/* {k:>2} */ "{e}",""".format(**locals()))
297 //
298 // cog.outl("}};")
299 // cog.outl()
300 // to_string_outl(ename)
301 // ]]]
303 static const std::array<const std::string, 4> timesync_mode_strings{{
304 /* 0 */ "NONE",
305 /* 1 */ "MAVLINK",
306 /* 2 */ "ONBOARD",
307 /* 3 */ "PASSTHROUGH",
308 }};
309 
310 std::string to_string(timesync_mode e)
311 {
312  size_t idx = enum_value(e);
313  if (idx >= timesync_mode_strings.size())
314  return std::to_string(idx);
315 
316  return timesync_mode_strings[idx];
317 }
318 // [[[end]]] (checksum: 2796eaa4f9361c2d7ca87f63e0401d4d)
319 
320 timesync_mode timesync_mode_from_str(const std::string &mode)
321 {
322  for (size_t idx = 0; idx < timesync_mode_strings.size(); idx++) {
323  if (timesync_mode_strings[idx] == mode) {
324  std::underlying_type<timesync_mode>::type rv = idx;
325  return static_cast<timesync_mode>(rv);
326  }
327  }
328 
329  ROS_ERROR_STREAM_NAMED("uas", "TM: Unknown mode: " << mode);
330  return timesync_mode::NONE;
331 }
332 
333 // [[[cog:
334 // ename = 'ADSB_ALTITUDE_TYPE'
335 // enum_name_is_value_outl(ename)
336 // ]]]
338 static const std::array<const std::string, 2> adsb_altitude_type_strings{{
339 /* 0 */ "PRESSURE_QNH", // Altitude reported from a Baro source using QNH reference
340 /* 1 */ "GEOMETRIC", // Altitude reported from a GNSS source
341 }};
342 
343 std::string to_string(ADSB_ALTITUDE_TYPE e)
344 {
345  size_t idx = enum_value(e);
346  if (idx >= adsb_altitude_type_strings.size())
347  return std::to_string(idx);
348 
349  return adsb_altitude_type_strings[idx];
350 }
351 // [[[end]]] (checksum: dc127bf29aefa513471d13c5a0e1e6ec)
352 
353 // [[[cog:
354 // ename = 'ADSB_EMITTER_TYPE'
355 // enum_name_is_value_outl(ename)
356 // ]]]
358 static const std::array<const std::string, 20> adsb_emitter_type_strings{{
359 /* 0 */ "NO_INFO",
360 /* 1 */ "LIGHT",
361 /* 2 */ "SMALL",
362 /* 3 */ "LARGE",
363 /* 4 */ "HIGH_VORTEX_LARGE",
364 /* 5 */ "HEAVY",
365 /* 6 */ "HIGHLY_MANUV",
366 /* 7 */ "ROTOCRAFT",
367 /* 8 */ "UNASSIGNED",
368 /* 9 */ "GLIDER",
369 /* 10 */ "LIGHTER_AIR",
370 /* 11 */ "PARACHUTE",
371 /* 12 */ "ULTRA_LIGHT",
372 /* 13 */ "UNASSIGNED2",
373 /* 14 */ "UAV",
374 /* 15 */ "SPACE",
375 /* 16 */ "UNASSGINED3",
376 /* 17 */ "EMERGENCY_SURFACE",
377 /* 18 */ "SERVICE_SURFACE",
378 /* 19 */ "POINT_OBSTACLE",
379 }};
380 
381 std::string to_string(ADSB_EMITTER_TYPE e)
382 {
383  size_t idx = enum_value(e);
384  if (idx >= adsb_emitter_type_strings.size())
385  return std::to_string(idx);
386 
387  return adsb_emitter_type_strings[idx];
388 }
389 // [[[end]]] (checksum: 713e0304603321e421131d8552d0f8e0)
390 
391 // [[[cog:
392 // ename = 'MAV_ESTIMATOR_TYPE'
393 // enum_name_is_value_outl(ename)
394 // ]]]
396 static const std::array<const std::string, 5> mav_estimator_type_strings{{
397 /* 1 */ "NAIVE", // This is a naive estimator without any real covariance feedback.
398 /* 2 */ "VISION", // Computer vision based estimate. Might be up to scale.
399 /* 3 */ "VIO", // Visual-inertial estimate.
400 /* 4 */ "GPS", // Plain GPS estimate.
401 /* 5 */ "GPS_INS", // Estimator integrating GPS and inertial sensing.
402 }};
403 
404 std::string to_string(MAV_ESTIMATOR_TYPE e)
405 {
406  size_t idx = enum_value(e);
407  if (idx >= mav_estimator_type_strings.size())
408  return std::to_string(idx);
409 
410  return mav_estimator_type_strings[idx];
411 }
412 // [[[end]]] (checksum: 47674f004bf6c515fdf999987b99e806)
413 
414 // [[[cog:
415 // ename = 'GPS_FIX_TYPE'
416 // enum_name_is_value_outl(ename)
417 // ]]]
419 static const std::array<const std::string, 9> gps_fix_type_strings{{
420 /* 0 */ "NO_GPS", // No GPS connected
421 /* 1 */ "NO_FIX", // No position information, GPS is connected
422 /* 2 */ "2D_FIX", // 2D position
423 /* 3 */ "3D_FIX", // 3D position
424 /* 4 */ "DGPS", // DGPS/SBAS aided 3D position
425 /* 5 */ "RTK_FLOAT", // RTK float, 3D position
426 /* 6 */ "RTK_FIXED", // RTK Fixed, 3D position
427 /* 7 */ "STATIC", // Static fixed, typically used for base stations
428 /* 8 */ "PPP", // PPP, 3D position.
429 }};
430 
431 std::string to_string(GPS_FIX_TYPE e)
432 {
433  size_t idx = enum_value(e);
434  if (idx >= gps_fix_type_strings.size())
435  return std::to_string(idx);
436 
437  return gps_fix_type_strings[idx];
438 }
439 // [[[end]]] (checksum: 7569b73b2d68ed1412bf0c36afeb131c)
440 
441 // [[[cog:
442 // ename = 'MAV_MISSION_RESULT'
443 // enum = get_enum(ename)
444 //
445 // array_outl(ename, enum)
446 // for k, e in enum:
447 // value = e.description
448 // sp = make_whitespace(30, value)
449 // cog.outl("""/* {k:>2} */ "{value}",{sp}// {e.description}""".format(**locals()))
450 //
451 // cog.outl("}};")
452 // cog.outl()
453 // to_string_outl(ename)
454 // ]]]
456 static const std::array<const std::string, 15> mav_mission_result_strings{{
457 /* 0 */ "mission accepted OK", // mission accepted OK
458 /* 1 */ "generic error / not accepting mission commands at all right now", // generic error / not accepting mission commands at all right now
459 /* 2 */ "coordinate frame is not supported", // coordinate frame is not supported
460 /* 3 */ "command is not supported", // command is not supported
461 /* 4 */ "mission item exceeds storage space", // mission item exceeds storage space
462 /* 5 */ "one of the parameters has an invalid value", // one of the parameters has an invalid value
463 /* 6 */ "param1 has an invalid value", // param1 has an invalid value
464 /* 7 */ "param2 has an invalid value", // param2 has an invalid value
465 /* 8 */ "param3 has an invalid value", // param3 has an invalid value
466 /* 9 */ "param4 has an invalid value", // param4 has an invalid value
467 /* 10 */ "x/param5 has an invalid value", // x/param5 has an invalid value
468 /* 11 */ "y/param6 has an invalid value", // y/param6 has an invalid value
469 /* 12 */ "param7 has an invalid value", // param7 has an invalid value
470 /* 13 */ "received waypoint out of sequence", // received waypoint out of sequence
471 /* 14 */ "not accepting any mission commands from this communication partner", // not accepting any mission commands from this communication partner
472 }};
473 
474 std::string to_string(MAV_MISSION_RESULT e)
475 {
476  size_t idx = enum_value(e);
477  if (idx >= mav_mission_result_strings.size())
478  return std::to_string(idx);
479 
480  return mav_mission_result_strings[idx];
481 }
482 // [[[end]]] (checksum: 06dac7af3755763d02332dea1ebf6a91)
483 
484 // [[[cog:
485 // ename = 'MAV_FRAME'
486 // enum_name_is_value_outl(ename)
487 // ]]]
489 static const std::array<const std::string, 20> mav_frame_strings{{
490 /* 0 */ "GLOBAL", // Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
491 /* 1 */ "LOCAL_NED", // Local coordinate frame, Z-down (x: north, y: east, z: down).
492 /* 2 */ "MISSION", // NOT a coordinate frame, indicates a mission command.
493 /* 3 */ "GLOBAL_RELATIVE_ALT", // Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect 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.
494 /* 4 */ "LOCAL_ENU", // Local coordinate frame, Z-up (x: east, y: north, z: up).
495 /* 5 */ "GLOBAL_INT", // Global coordinate frame, WGS84 coordinate system. 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).
496 /* 6 */ "GLOBAL_RELATIVE_ALT_INT", // Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect 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.
497 /* 7 */ "LOCAL_OFFSET_NED", // Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
498 /* 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.
499 /* 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.
500 /* 10 */ "GLOBAL_TERRAIN_ALT", // Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to 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.
501 /* 11 */ "GLOBAL_TERRAIN_ALT_INT", // Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to 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.
502 /* 12 */ "BODY_FRD", // Body fixed frame of reference, Z-down (x: forward, y: right, z: down).
503 /* 13 */ "BODY_FLU", // Body fixed frame of reference, Z-up (x: forward, y: left, z: up).
504 /* 14 */ "MOCAP_NED", // Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down).
505 /* 15 */ "MOCAP_ENU", // Odometry local coordinate frame of data given by a motion capture system, Z-up (x: east, y: north, z: up).
506 /* 16 */ "VISION_NED", // Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down).
507 /* 17 */ "VISION_ENU", // Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: east, y: north, z: up).
508 /* 18 */ "ESTIM_NED", // Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down).
509 /* 19 */ "ESTIM_ENU", // Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: east, y: noth, z: up).
510 }};
511 
512 std::string to_string(MAV_FRAME e)
513 {
514  size_t idx = enum_value(e);
515  if (idx >= mav_frame_strings.size())
516  return std::to_string(idx);
517 
518  return mav_frame_strings[idx];
519 }
520 // [[[end]]] (checksum: 51190f7ce3474a7189c11eb3e63b9322)
521 
522 // [[[cog:
523 // ename = 'MAV_COMPONENT'
524 // suffix = 'MAV_COMP_ID'
525 // enum = get_enum(ename)
526 //
527 // cog.outl(f"static const std::unordered_map<size_t, const std::string> {suffix.lower()}_strings{{{{")
528 // for k, e in enum:
529 // name_short = e.name[len(suffix) + 1:]
530 // sp = make_whitespace(30, name_short)
531 // if e.description:
532 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},{sp}// {e.description}""")
533 // else:
534 // cog.outl(f"""{{ {k:>3}, "{name_short}" }},""")
535 //
536 // cog.outl("}};")
537 // ]]]
538 static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
539 { 0, "ALL" },
540 { 1, "AUTOPILOT1" },
541 { 100, "CAMERA" },
542 { 101, "CAMERA2" },
543 { 102, "CAMERA3" },
544 { 103, "CAMERA4" },
545 { 104, "CAMERA5" },
546 { 105, "CAMERA6" },
547 { 140, "SERVO1" },
548 { 141, "SERVO2" },
549 { 142, "SERVO3" },
550 { 143, "SERVO4" },
551 { 144, "SERVO5" },
552 { 145, "SERVO6" },
553 { 146, "SERVO7" },
554 { 147, "SERVO8" },
555 { 148, "SERVO9" },
556 { 149, "SERVO10" },
557 { 150, "SERVO11" },
558 { 151, "SERVO12" },
559 { 152, "SERVO13" },
560 { 153, "SERVO14" },
561 { 154, "GIMBAL" },
562 { 155, "LOG" },
563 { 156, "ADSB" },
564 { 157, "OSD" }, // On Screen Display (OSD) devices for video links
565 { 158, "PERIPHERAL" }, // Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol
566 { 159, "QX1_GIMBAL" },
567 { 160, "FLARM" },
568 { 180, "MAPPER" },
569 { 190, "MISSIONPLANNER" },
570 { 195, "PATHPLANNER" },
571 { 200, "IMU" },
572 { 201, "IMU_2" },
573 { 202, "IMU_3" },
574 { 220, "GPS" },
575 { 221, "GPS2" },
576 { 240, "UDP_BRIDGE" },
577 { 241, "UART_BRIDGE" },
578 { 250, "SYSTEM_CONTROL" },
579 }};
580 // [[[end]]] (checksum: 9769958883e98b63a634629710a11131)
581 
582 std::string to_string(MAV_COMPONENT e)
583 {
584  size_t idx = enum_value(e);
585  auto it = mav_comp_id_strings.find(idx);
586 
587  if (it == mav_comp_id_strings.end())
588  return std::to_string(idx);
589 
590  return it->second;
591 }
592 // [[[end]]] (checksum: 849fca3985365a416a5a242b9af0ff7c)
593 
594 MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
595 {
596  for (size_t idx = 0; idx < mav_frame_strings.size(); idx++) {
597  if (mav_frame_strings[idx] == mav_frame) {
598  std::underlying_type<MAV_FRAME>::type rv = idx;
599  return static_cast<MAV_FRAME>(rv);
600  }
601  }
602 
603  ROS_ERROR_STREAM_NAMED("uas", "FRAME: Unknown MAV_FRAME: " << mav_frame);
604  return MAV_FRAME::LOCAL_NED;
605 }
606 
607 MAV_TYPE mav_type_from_str(const std::string &mav_type)
608 {
609  for (size_t idx = 0; idx < mav_type_names.size(); idx++) {
610  if (mav_type_names[idx] == mav_type) {
611  std::underlying_type<MAV_TYPE>::type rv = idx;
612  return static_cast<MAV_TYPE>(rv);
613  }
614  }
615  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown MAV_TYPE: " << mav_type);
616  return MAV_TYPE::GENERIC;
617 }
618 
619 // [[[cog:
620 // ename = 'MAV_DISTANCE_SENSOR'
621 // enum_name_is_value_outl(ename)
622 // ]]]
624 static const std::array<const std::string, 5> mav_distance_sensor_strings{{
625 /* 0 */ "LASER", // Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
626 /* 1 */ "ULTRASOUND", // Ultrasound rangefinder, e.g. MaxBotix units
627 /* 2 */ "INFRARED", // Infrared rangefinder, e.g. Sharp units
628 /* 3 */ "RADAR", // Radar type, e.g. uLanding units
629 /* 4 */ "UNKNOWN", // Broken or unknown type, e.g. analog units
630 }};
631 
632 std::string to_string(MAV_DISTANCE_SENSOR e)
633 {
634  size_t idx = enum_value(e);
635  if (idx >= mav_distance_sensor_strings.size())
636  return std::to_string(idx);
637 
638  return mav_distance_sensor_strings[idx];
639 }
640 // [[[end]]] (checksum: 3f792ad01cdb3f2315a8907f578ab5b3)
641 
642 // [[[cog:
643 // ename = 'LANDING_TARGET_TYPE'
644 // enum_name_is_value_outl(ename)
645 // ]]]
647 static const std::array<const std::string, 4> landing_target_type_strings{{
648 /* 0 */ "LIGHT_BEACON", // Landing target signaled by light beacon (ex: IR-LOCK)
649 /* 1 */ "RADIO_BEACON", // Landing target signaled by radio beacon (ex: ILS, NDB)
650 /* 2 */ "VISION_FIDUCIAL", // Landing target represented by a fiducial marker (ex: ARTag)
651 /* 3 */ "VISION_OTHER", // Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
652 }};
653 
654 std::string to_string(LANDING_TARGET_TYPE e)
655 {
656  size_t idx = enum_value(e);
657  if (idx >= landing_target_type_strings.size())
658  return std::to_string(idx);
659 
660  return landing_target_type_strings[idx];
661 }
662 // [[[end]]] (checksum: a42789c10cbebd5bc253abca2a07289b)
663 
664 LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
665 {
666  for (size_t idx = 0; idx < landing_target_type_strings.size(); idx++) {
667  if (landing_target_type_strings[idx] == landing_target_type) {
668  std::underlying_type<LANDING_TARGET_TYPE>::type rv = idx;
669  return static_cast<LANDING_TARGET_TYPE>(rv);
670  }
671  }
672  ROS_ERROR_STREAM_NAMED("uas", "TYPE: Unknown LANDING_TARGET_TYPE: " << landing_target_type << ". Defaulting to LIGHT_BEACON");
673  return LANDING_TARGET_TYPE::LIGHT_BEACON;
674 }
675 
676 } // namespace utils
677 } // namespace mavros
std::string to_name(MAV_TYPE e)
static const std::array< const std::string, 20 > mav_autopilot_strings
MAV_AUTOPILOT values.
static const std::array< const std::string, 4 > timesync_mode_strings
timesync_mode values
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)
static const std::array< const std::string, 15 > mav_mission_result_strings
MAV_MISSION_RESULT values.
static const std::array< const std::string, 5 > mav_estimator_type_strings
MAV_ESTIMATOR_TYPE values.
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, 33 > mav_type_names
MAV_TYPE values.
static const std::array< const std::string, 20 > mav_frame_strings
MAV_FRAME values.
static const std::array< const std::string, 20 > adsb_emitter_type_strings
ADSB_EMITTER_TYPE values.
static const std::array< const std::string, 33 > mav_type_strings
MAV_TYPE values.
static const std::array< const std::string, 2 > adsb_altitude_type_strings
ADSB_ALTITUDE_TYPE values.
mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
std::string to_string(timesync_mode e)
static const std::array< const std::string, 9 > gps_fix_type_strings
GPS_FIX_TYPE values.
static const std::unordered_map< size_t, const std::string > mav_comp_id_strings
timesync_mode timesync_mode_from_str(const std::string &mode)
Retrieve timesync mode from name.
static const std::array< const std::string, 4 > landing_target_type_strings
LANDING_TARGET_TYPE values.
mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
Retrieve landing target type from alias name.
static const std::array< const std::string, 9 > mav_state_strings
MAV_STATE values.
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55


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