Browse Source

Minor cleanups in docs and output

sbg
Lorenz Meier 12 years ago
parent
commit
340323830c
  1. 3
      apps/mavlink/mavlink.c
  2. 12
      apps/uORB/topics/vehicle_global_position_setpoint.h

3
apps/mavlink/mavlink.c

@ -547,6 +547,9 @@ int mavlink_thread_main(int argc, char *argv[]) @@ -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);

12
apps/uORB/topics/vehicle_global_position_setpoint.h

@ -60,12 +60,12 @@ @@ -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…
Cancel
Save