Permalink
Browse files

Updated documentation, extenden PIXHAWK message set

  • Loading branch information...
1 parent 49db989 commit 59af398aa6c1272e191ad883fdef5df2d47b63f0 lm committed Mar 7, 2011
View
@@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
- * Generated on Saturday, February 26 2011, 13:25 UTC
+ * Generated on Wednesday, March 2 2011, 13:12 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@@ -57,7 +57,7 @@ enum MAV_CMD
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system.Camera ID (-1 for all)Transmission: 0: disabled, 1: enabled compressed, 2: enabled rawTransmission mode: 0: video stream, >0: single images every n seconds (decimal)Recording: 0: disabled, 1: enabled compressed, 2: enabled rawEmptyEmptyEmpty*/
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode.Gyro calibration: 0: no, 1: yesMagnetometer calibration: 0: no, 1: yesRadio calibration: 0: no, 1: yesRadio calibration: 0: no, 1: yesEmptyEmptyEmpty*/
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode.Gyro calibration: 0: no, 1: yesMagnetometer calibration: 0: no, 1: yesGround pressure: 0: no, 1: yesRadio calibration: 0: no, 1: yesEmptyEmptyEmpty*/
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMMission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMReservedReservedEmptyEmptyEmpty*/
MAV_CMD_ENUM_END
};
View
@@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
- * Generated on Saturday, February 26 2011, 13:25 UTC
+ * Generated on Wednesday, March 2 2011, 13:12 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
@@ -4,8 +4,8 @@
typedef struct __mavlink_global_position_int_t
{
- int32_t lat; ///< Latitude / X Position, expressed as * 1E7
- int32_t lon; ///< Longitude / Y Position, expressed as * 1E7
+ int32_t lat; ///< Latitude, expressed as * 1E7
+ int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
@@ -21,8 +21,8 @@ typedef struct __mavlink_global_position_int_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param lat Latitude / X Position, expressed as * 1E7
- * @param lon Longitude / Y Position, expressed as * 1E7
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -34,8 +34,8 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
- i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
- i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
+ i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+ i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
@@ -50,8 +50,8 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
- * @param lat Latitude / X Position, expressed as * 1E7
- * @param lon Longitude / Y Position, expressed as * 1E7
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -63,8 +63,8 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
- i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
- i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
+ i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
+ i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
@@ -90,8 +90,8 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
*
- * @param lat Latitude / X Position, expressed as * 1E7
- * @param lon Longitude / Y Position, expressed as * 1E7
+ * @param lat Latitude, expressed as * 1E7
+ * @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -112,7 +112,7 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan,
/**
* @brief Get field lat from global_position_int message
*
- * @return Latitude / X Position, expressed as * 1E7
+ * @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
@@ -127,7 +127,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess
/**
* @brief Get field lon from global_position_int message
*
- * @return Longitude / Y Position, expressed as * 1E7
+ * @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
@@ -6,9 +6,9 @@ typedef struct __mavlink_gps_set_global_origin_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
- uint32_t latitude; ///< global x position * 1E7
- uint32_t longitude; ///< global y position * 1E7
- uint32_t altitude; ///< global z position * 1000
+ uint32_t latitude; ///< global position * 1E7
+ uint32_t longitude; ///< global position * 1E7
+ uint32_t altitude; ///< global position * 1000
} mavlink_gps_set_global_origin_t;
@@ -22,9 +22,9 @@ typedef struct __mavlink_gps_set_global_origin_t
*
* @param target_system System ID
* @param target_component Component ID
- * @param latitude global x position * 1E7
- * @param longitude global y position * 1E7
- * @param altitude global z position * 1000
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude)
@@ -34,9 +34,9 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id,
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
- i += put_uint32_t_by_index(latitude, i, msg->payload); // global x position * 1E7
- i += put_uint32_t_by_index(longitude, i, msg->payload); // global y position * 1E7
- i += put_uint32_t_by_index(altitude, i, msg->payload); // global z position * 1000
+ i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7
+ i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7
+ i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@@ -49,9 +49,9 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id,
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
- * @param latitude global x position * 1E7
- * @param longitude global y position * 1E7
- * @param altitude global z position * 1000
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude)
@@ -61,9 +61,9 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t syste
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
- i += put_uint32_t_by_index(latitude, i, msg->payload); // global x position * 1E7
- i += put_uint32_t_by_index(longitude, i, msg->payload); // global y position * 1E7
- i += put_uint32_t_by_index(altitude, i, msg->payload); // global z position * 1000
+ i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7
+ i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7
+ i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@@ -87,9 +87,9 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_i
*
* @param target_system System ID
* @param target_component Component ID
- * @param latitude global x position * 1E7
- * @param longitude global y position * 1E7
- * @param altitude global z position * 1000
+ * @param latitude global position * 1E7
+ * @param longitude global position * 1E7
+ * @param altitude global position * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -126,7 +126,7 @@ static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(con
/**
* @brief Get field latitude from gps_set_global_origin message
*
- * @return global x position * 1E7
+ * @return global position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
{
@@ -141,7 +141,7 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavl
/**
* @brief Get field longitude from gps_set_global_origin message
*
- * @return global y position * 1E7
+ * @return global position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
{
@@ -156,7 +156,7 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mav
/**
* @brief Get field altitude from gps_set_global_origin message
*
- * @return global z position * 1000
+ * @return global position * 1000
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
{
@@ -15,8 +15,8 @@ typedef struct __mavlink_waypoint_t
float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- float x; ///< PARAM5 / local: x position, global: longitude
- float y; ///< PARAM6 / y position: global: latitude
+ float x; ///< PARAM5 / local: x position, global: latitude
+ float y; ///< PARAM6 / y position: global: longitude
float z; ///< PARAM7 / z position: global: altitude
} mavlink_waypoint_t;
@@ -40,8 +40,8 @@ typedef struct __mavlink_waypoint_t
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- * @param x PARAM5 / local: x position, global: longitude
- * @param y PARAM6 / y position: global: latitude
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -61,8 +61,8 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: longitude
- i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: latitude
+ i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
+ i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
return mavlink_finalize_message(msg, system_id, component_id, i);
@@ -85,8 +85,8 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- * @param x PARAM5 / local: x position, global: longitude
- * @param y PARAM6 / y position: global: latitude
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -106,8 +106,8 @@ static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t
i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: longitude
- i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: latitude
+ i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
+ i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
@@ -141,8 +141,8 @@ static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t co
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- * @param x PARAM5 / local: x position, global: longitude
- * @param y PARAM6 / y position: global: latitude
+ * @param x PARAM5 / local: x position, global: latitude
+ * @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -293,7 +293,7 @@ static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg
/**
* @brief Get field x from waypoint message
*
- * @return PARAM5 / local: x position, global: longitude
+ * @return PARAM5 / local: x position, global: latitude
*/
static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
{
@@ -308,7 +308,7 @@ static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
/**
* @brief Get field y from waypoint message
*
- * @return PARAM6 / y position: global: latitude
+ * @return PARAM6 / y position: global: longitude
*/
static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
{
@@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
- * Generated on Saturday, February 26 2011, 13:25 UTC
+ * Generated on Wednesday, March 2 2011, 13:12 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
Oops, something went wrong.

0 comments on commit 59af398

Please sign in to comment.