diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2012-11-18 16:17:09 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2012-11-18 16:17:09 +0100 |
commit | 340323830c34d40bf159d33ed24333d30a7787f2 (patch) | |
tree | 9525589e7ee869f24747c1af23c5a05c534ea48f /apps | |
parent | e9acc18df4e4d870ca20d10e100a132cf4a15631 (diff) | |
download | px4-firmware-340323830c34d40bf159d33ed24333d30a7787f2.tar.gz px4-firmware-340323830c34d40bf159d33ed24333d30a7787f2.tar.bz2 px4-firmware-340323830c34d40bf159d33ed24333d30a7787f2.zip |
Minor cleanups in docs and output
Diffstat (limited to 'apps')
-rw-r--r-- | apps/mavlink/mavlink.c | 3 | ||||
-rw-r--r-- | apps/uORB/topics/vehicle_global_position_setpoint.h | 12 |
2 files changed, 9 insertions, 6 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 991bbfbab..b393620e2 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -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); diff --git a/apps/uORB/topics/vehicle_global_position_setpoint.h b/apps/uORB/topics/vehicle_global_position_setpoint.h index b73e2a363..eec6a8229 100644 --- a/apps/uORB/topics/vehicle_global_position_setpoint.h +++ b/apps/uORB/topics/vehicle_global_position_setpoint.h @@ -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 */ }; /** |