added SET_MAG_OFFSETS magnetometer message

this allows reset of the mag offsets without wiping your EEPROM

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3088 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-08-13 09:00:21 +00:00
parent 32c576f28c
commit 69b6e5225a
6 changed files with 194 additions and 5 deletions

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Saturday, August 13 2011, 04:23 UTC
* Generated on Saturday, August 13 2011, 08:44 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
@ -34,12 +34,13 @@ extern "C" {
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#ifdef __cplusplus
}

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Saturday, August 13 2011, 04:23 UTC
* Generated on Saturday, August 13 2011, 08:44 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -0,0 +1,178 @@
// MESSAGE SET_MAG_OFFSETS PACKING
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
typedef struct __mavlink_set_mag_offsets_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int16_t mag_ofs_x; ///< magnetometer X offset
int16_t mag_ofs_y; ///< magnetometer Y offset
int16_t mag_ofs_z; ///< magnetometer Z offset
} mavlink_set_mag_offsets_t;
/**
* @brief Pack a set_mag_offsets message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
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_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a set_mag_offsets message
* @param system_id ID of this system
* @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 target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_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, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
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_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a set_mag_offsets struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_mag_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
mavlink_message_t msg;
mavlink_msg_set_mag_offsets_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SET_MAG_OFFSETS UNPACKING
/**
* @brief Get field target_system from set_mag_offsets message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from set_mag_offsets message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mag_ofs_x from set_mag_offsets message
*
* @return magnetometer X offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field mag_ofs_y from set_mag_offsets message
*
* @return magnetometer Y offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field mag_ofs_z from set_mag_offsets message
*
* @return magnetometer Z offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Decode a set_mag_offsets message into a struct
*
* @param msg The message to decode
* @param set_mag_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
{
set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
}

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Saturday, August 13 2011, 04:23 UTC
* Generated on Saturday, August 13 2011, 08:44 UTC
*/
#ifndef COMMON_H
#define COMMON_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Saturday, August 13 2011, 04:23 UTC
* Generated on Saturday, August 13 2011, 08:44 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -25,5 +25,15 @@
<field type="float" name="accel_cal_y">accel Y calibration</field>
<field type="float" name="accel_cal_z">accel Z calibration</field>
</message>
<message id="151" name="SET_MAG_OFFSETS">
<description>set the magnetometer offsets</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
</message>
</messages>
</mavlink>