forked from Archive/PX4-Autopilot
Minor cleanups in docs and output
This commit is contained in:
parent
e9acc18df4
commit
340323830c
|
@ -547,6 +547,9 @@ int mavlink_thread_main(int argc, char *argv[])
|
|||
/* print welcome text */
|
||||
warnx("MAVLink v1.0 serial interface starting...");
|
||||
|
||||
/* inform about mode */
|
||||
warnx((mavlink_link_mode == MAVLINK_INTERFACE_MODE_ONBOARD) ? "ONBOARD MODE" : "DOWNLINK MODE");
|
||||
|
||||
/* Flush stdout in case MAVLink is about to take it over */
|
||||
fflush(stdout);
|
||||
|
||||
|
|
|
@ -60,12 +60,12 @@
|
|||
struct vehicle_global_position_setpoint_s
|
||||
{
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
int32_t lat; /**< latitude in degrees * 1E7 */
|
||||
int32_t lon; /**< longitude in degrees * 1E7 */
|
||||
float altitude; /**< altitude in meters */
|
||||
float yaw; /**< in radians NED -PI..+PI */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
bool is_loiter; /**< true if loitering is enabled */
|
||||
int32_t lat; /**< latitude in degrees * 1E7 */
|
||||
int32_t lon; /**< longitude in degrees * 1E7 */
|
||||
float altitude; /**< altitude in meters */
|
||||
float yaw; /**< in radians NED -PI..+PI */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
bool is_loiter; /**< true if loitering is enabled */
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
Loading…
Reference in New Issue