mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
Added airspeed message to mavlink.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1102 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b82ba72ab2
commit
415786a480
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Tuesday, December 7 2010, 13:34 UTC
|
||||
* Generated on Friday, December 10 2010, 07:24 UTC
|
||||
*/
|
||||
#ifndef COMMON_H
|
||||
#define COMMON_H
|
||||
@ -65,6 +65,7 @@ extern "C" {
|
||||
#include "./mavlink_msg_manual_control.h"
|
||||
#include "./mavlink_msg_debug_vect.h"
|
||||
#include "./mavlink_msg_gps_local_origin_set.h"
|
||||
#include "./mavlink_msg_airspeed.h"
|
||||
#include "./mavlink_msg_statustext.h"
|
||||
#include "./mavlink_msg_debug.h"
|
||||
#ifdef __cplusplus
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Tuesday, December 7 2010, 13:34 UTC
|
||||
* Generated on Friday, December 10 2010, 07:24 UTC
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
74
libraries/GCS_MAVLink/include/common/mavlink_msg_airspeed.h
Normal file
74
libraries/GCS_MAVLink/include/common/mavlink_msg_airspeed.h
Normal file
@ -0,0 +1,74 @@
|
||||
// MESSAGE AIRSPEED PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_AIRSPEED 72
|
||||
|
||||
typedef struct __mavlink_airspeed_t
|
||||
{
|
||||
float airspeed; ///< meters/second
|
||||
|
||||
} mavlink_airspeed_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Send a airspeed message
|
||||
*
|
||||
* @param airspeed meters/second
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_airspeed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
|
||||
|
||||
i += put_float_by_index(airspeed, i, msg->payload); //meters/second
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_airspeed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
|
||||
|
||||
i += put_float_by_index(airspeed, i, msg->payload); //meters/second
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_airspeed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
|
||||
{
|
||||
return mavlink_msg_airspeed_pack(system_id, component_id, msg, airspeed->airspeed);
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_airspeed_send(mavlink_channel_t chan, float airspeed)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_airspeed_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE AIRSPEED UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field airspeed from airspeed message
|
||||
*
|
||||
* @return meters/second
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_get_airspeed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload)[0];
|
||||
r.b[2] = (msg->payload)[1];
|
||||
r.b[1] = (msg->payload)[2];
|
||||
r.b[0] = (msg->payload)[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
static inline void mavlink_msg_airspeed_decode(const mavlink_message_t* msg, mavlink_airspeed_t* airspeed)
|
||||
{
|
||||
airspeed->airspeed = mavlink_msg_airspeed_get_airspeed(msg);
|
||||
}
|
@ -409,6 +409,11 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
|
||||
<field name="y" type="float">Local Y coordinate in meters</field>
|
||||
<field name="z" type="float">Local Z coordinate in meters</field>
|
||||
</message>
|
||||
|
||||
<message name="AIRSPEED" id="72">
|
||||
<description>The calculated airspeed </description>
|
||||
<field name="airspeed" type="float">meters/second</field>
|
||||
</message>
|
||||
|
||||
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user