Commit 9a705c22 authored by LM's avatar LM

Updated MAVLink

parent 738a310e
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wednesday, August 10 2011, 09:07 UTC
* Generated on Thursday, August 11 2011, 07:25 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......@@ -275,6 +275,8 @@ enum MAV_CMD
#include "./mavlink_msg_safety_allowed_area.h"
#include "./mavlink_msg_set_roll_pitch_yaw.h"
#include "./mavlink_msg_set_roll_pitch_yaw_speed.h"
#include "./mavlink_msg_roll_pitch_yaw_setpoint.h"
#include "./mavlink_msg_roll_pitch_yaw_speed_setpoint.h"
#include "./mavlink_msg_attitude_controller_output.h"
#include "./mavlink_msg_position_controller_output.h"
#include "./mavlink_msg_nav_controller_output.h"
......@@ -300,7 +302,7 @@ enum MAV_CMD
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 127, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 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, 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, 138, 43, 141, 211, 144 }
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 44, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 79, 252, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 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, 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, 138, 43, 141, 211, 144 }
#ifdef __cplusplus
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, August 10 2011, 09:07 UTC
* Generated on Thursday, August 11 2011, 07:25 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
// MESSAGE ROLL_PITCH_YAW_SETPOINT PACKING
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT 57
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT_LEN 16
#define MAVLINK_MSG_57_LEN 16
typedef struct __mavlink_roll_pitch_yaw_setpoint_t
{
uint32_t time_ms; ///< Timestamp in milliseconds since system boot
float roll; ///< Desired roll angle in radians
float pitch; ///< Desired pitch angle in radians
float yaw; ///< Desired yaw angle in radians
} mavlink_roll_pitch_yaw_setpoint_t;
/**
* @brief Pack a roll_pitch_yaw_setpoint 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 time_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t time_ms, float roll, float pitch, float yaw)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll = roll; // float:Desired roll angle in radians
p->pitch = pitch; // float:Desired pitch angle in radians
p->yaw = yaw; // float:Desired yaw angle in radians
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT_LEN);
}
/**
* @brief Pack a roll_pitch_yaw_setpoint 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 time_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t time_ms, float roll, float pitch, float yaw)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll = roll; // float:Desired roll angle in radians
p->pitch = pitch; // float:Desired pitch angle in radians
p->yaw = yaw; // float:Desired yaw angle in radians
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT_LEN);
}
/**
* @brief Encode a roll_pitch_yaw_setpoint 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 roll_pitch_yaw_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_setpoint_t* roll_pitch_yaw_setpoint)
{
return mavlink_msg_roll_pitch_yaw_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_setpoint->time_ms, roll_pitch_yaw_setpoint->roll, roll_pitch_yaw_setpoint->pitch, roll_pitch_yaw_setpoint->yaw);
}
/**
* @brief Send a roll_pitch_yaw_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_roll_pitch_yaw_setpoint_send(mavlink_channel_t chan, uint32_t time_ms, float roll, float pitch, float yaw)
{
mavlink_header_t hdr;
mavlink_roll_pitch_yaw_setpoint_t payload;
uint16_t checksum;
mavlink_roll_pitch_yaw_setpoint_t *p = &payload;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll = roll; // float:Desired roll angle in radians
p->pitch = pitch; // float:Desired pitch angle in radians
p->yaw = yaw; // float:Desired yaw angle in radians
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT_LEN;
hdr.msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SETPOINT;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
crc_init(&checksum);
checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte
mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
}
#endif
// MESSAGE ROLL_PITCH_YAW_SETPOINT UNPACKING
/**
* @brief Get field time_ms from roll_pitch_yaw_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_setpoint_get_time_ms(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
return (uint32_t)(p->time_ms);
}
/**
* @brief Get field roll from roll_pitch_yaw_setpoint message
*
* @return Desired roll angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_setpoint_get_roll(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
return (float)(p->roll);
}
/**
* @brief Get field pitch from roll_pitch_yaw_setpoint message
*
* @return Desired pitch angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_setpoint_get_pitch(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
return (float)(p->pitch);
}
/**
* @brief Get field yaw from roll_pitch_yaw_setpoint message
*
* @return Desired yaw angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_setpoint_get_yaw(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_setpoint_t *p = (mavlink_roll_pitch_yaw_setpoint_t *)&msg->payload[0];
return (float)(p->yaw);
}
/**
* @brief Decode a roll_pitch_yaw_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_setpoint_t* roll_pitch_yaw_setpoint)
{
memcpy( roll_pitch_yaw_setpoint, msg->payload, sizeof(mavlink_roll_pitch_yaw_setpoint_t));
}
// MESSAGE ROLL_PITCH_YAW_SPEED_SETPOINT PACKING
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT 58
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT_LEN 16
#define MAVLINK_MSG_58_LEN 16
typedef struct __mavlink_roll_pitch_yaw_speed_setpoint_t
{
uint32_t time_ms; ///< Timestamp in milliseconds since system boot
float roll_speed; ///< Desired roll angular speed in rad/s
float pitch_speed; ///< Desired pitch angular speed in rad/s
float yaw_speed; ///< Desired yaw angular speed in rad/s
} mavlink_roll_pitch_yaw_speed_setpoint_t;
/**
* @brief Pack a roll_pitch_yaw_speed_setpoint 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 time_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t time_ms, float roll_speed, float pitch_speed, float yaw_speed)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll_speed = roll_speed; // float:Desired roll angular speed in rad/s
p->pitch_speed = pitch_speed; // float:Desired pitch angular speed in rad/s
p->yaw_speed = yaw_speed; // float:Desired yaw angular speed in rad/s
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT_LEN);
}
/**
* @brief Pack a roll_pitch_yaw_speed_setpoint 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 time_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t time_ms, float roll_speed, float pitch_speed, float yaw_speed)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll_speed = roll_speed; // float:Desired roll angular speed in rad/s
p->pitch_speed = pitch_speed; // float:Desired pitch angular speed in rad/s
p->yaw_speed = yaw_speed; // float:Desired yaw angular speed in rad/s
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT_LEN);
}
/**
* @brief Encode a roll_pitch_yaw_speed_setpoint 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 roll_pitch_yaw_speed_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_setpoint_t* roll_pitch_yaw_speed_setpoint)
{
return mavlink_msg_roll_pitch_yaw_speed_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_setpoint->time_ms, roll_pitch_yaw_speed_setpoint->roll_speed, roll_pitch_yaw_speed_setpoint->pitch_speed, roll_pitch_yaw_speed_setpoint->yaw_speed);
}
/**
* @brief Send a roll_pitch_yaw_speed_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_roll_pitch_yaw_speed_setpoint_send(mavlink_channel_t chan, uint32_t time_ms, float roll_speed, float pitch_speed, float yaw_speed)
{
mavlink_header_t hdr;
mavlink_roll_pitch_yaw_speed_setpoint_t payload;
uint16_t checksum;
mavlink_roll_pitch_yaw_speed_setpoint_t *p = &payload;
p->time_ms = time_ms; // uint32_t:Timestamp in milliseconds since system boot
p->roll_speed = roll_speed; // float:Desired roll angular speed in rad/s
p->pitch_speed = pitch_speed; // float:Desired pitch angular speed in rad/s
p->yaw_speed = yaw_speed; // float:Desired yaw angular speed in rad/s
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT_LEN;
hdr.msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_SETPOINT;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
crc_init(&checksum);
checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte
mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
}
#endif
// MESSAGE ROLL_PITCH_YAW_SPEED_SETPOINT UNPACKING
/**
* @brief Get field time_ms from roll_pitch_yaw_speed_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_setpoint_get_time_ms(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
return (uint32_t)(p->time_ms);
}
/**
* @brief Get field roll_speed from roll_pitch_yaw_speed_setpoint message
*
* @return Desired roll angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_setpoint_get_roll_speed(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
return (float)(p->roll_speed);
}
/**
* @brief Get field pitch_speed from roll_pitch_yaw_speed_setpoint message
*
* @return Desired pitch angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_setpoint_get_pitch_speed(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
return (float)(p->pitch_speed);
}
/**
* @brief Get field yaw_speed from roll_pitch_yaw_speed_setpoint message
*
* @return Desired yaw angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_setpoint_get_yaw_speed(const mavlink_message_t* msg)
{
mavlink_roll_pitch_yaw_speed_setpoint_t *p = (mavlink_roll_pitch_yaw_speed_setpoint_t *)&msg->payload[0];
return (float)(p->yaw_speed);
}
/**
* @brief Decode a roll_pitch_yaw_speed_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_speed_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_speed_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_setpoint_t* roll_pitch_yaw_speed_setpoint)
{
memcpy( roll_pitch_yaw_speed_setpoint, msg->payload, sizeof(mavlink_roll_pitch_yaw_speed_setpoint_t));
}
......@@ -1011,6 +1011,20 @@
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
</message>
<message id="57" name="ROLL_PITCH_YAW_SETPOINT">
<description>Setpoint in roll, pitch, yaw currently active on the system.</description>
<field type="uint32_t" name="time_ms">Timestamp in milliseconds since system boot</field>
<field type="float" name="roll">Desired roll angle in radians</field>
<field type="float" name="pitch">Desired pitch angle in radians</field>
<field type="float" name="yaw">Desired yaw angle in radians</field>
</message>
<message id="58" name="ROLL_PITCH_YAW_SPEED_SETPOINT">
<description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description>
<field type="uint32_t" name="time_ms">Timestamp in milliseconds since system boot</field>
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
</message>
<message id="60" name="ATTITUDE_CONTROLLER_OUTPUT">
<description>The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight.</description>
<field type="uint8_t" name="enabled">1: enabled, 0: disabled</field>
......
This diff is collapsed.
......@@ -47,7 +47,7 @@ enum MAVLINK_WPM_CODES
/* WAYPOINT MANAGER - MISSION LIB */
#define MAVLINK_WPM_MAX_WP_COUNT 100
#define MAVLINK_WPM_MAX_WP_COUNT 30
#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates
#define MAVLINK_WPM_TEXT_FEEDBACK 1 ///< Report back status information as text
#define MAVLINK_WPM_SYSTEM_ID 1
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment