Browse Source

Merge branch 'rates_setpoint' into fixedwing_outdoor

sbg
Lorenz Meier 12 years ago
parent
commit
7d485c117b
  1. 78
      apps/mavlink/mavlink_parameters.c
  2. 23
      apps/mavlink/orb_listener.c
  3. 2
      apps/mavlink/orb_topics.h
  4. 6
      mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
  5. 2
      mavlink/include/mavlink/v1.0/ardupilotmega/version.h
  6. 8
      mavlink/include/mavlink/v1.0/common/common.h
  7. 276
      mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
  8. 232
      mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
  9. 108
      mavlink/include/mavlink/v1.0/common/testsuite.h
  10. 2
      mavlink/include/mavlink/v1.0/common/version.h
  11. 6
      mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
  12. 2
      mavlink/include/mavlink/v1.0/matrixpilot/version.h
  13. 6
      mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
  14. 2
      mavlink/include/mavlink/v1.0/pixhawk/version.h
  15. 6
      mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
  16. 2
      mavlink/include/mavlink/v1.0/sensesoar/version.h

78
apps/mavlink/mavlink_parameters.c

@ -72,20 +72,6 @@ static unsigned int mavlink_param_queue_index = 0; @@ -72,20 +72,6 @@ static unsigned int mavlink_param_queue_index = 0;
*/
void mavlink_pm_callback(void *arg, param_t param);
/**
* Save parameters to EEPROM.
*
* Stores the parameters to /eeprom/parameters
*/
static int mavlink_pm_save_eeprom(void);
/**
* Load parameters from EEPROM.
*
* Loads the parameters from /eeprom/parameters
*/
static int mavlink_pm_load_eeprom(void);
void mavlink_pm_callback(void *arg, param_t param)
{
mavlink_pm_send_param(param);
@ -232,69 +218,5 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess @@ -232,69 +218,5 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess
}
} break;
// case MAVLINK_MSG_ID_COMMAND_LONG: {
// mavlink_command_long_t cmd_mavlink;
// mavlink_msg_command_long_decode(msg, &cmd_mavlink);
// uint8_t result = MAV_RESULT_UNSUPPORTED;
// if (cmd_mavlink.target_system == mavlink_system.sysid &&
// ((cmd_mavlink.target_component == mavlink_system.compid) ||(cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
// // XXX move this to LOW PRIO THREAD of commander app
// /* preflight parameter load / store */
// if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_STORAGE) {
// /* Read all parameters from EEPROM to RAM */
// if (((int)(cmd_mavlink.param1)) == 0) {
// /* read all parameters from EEPROM to RAM */
// int read_ret = param_load_default();
// if (read_ret == OK) {
// //printf("[mavlink pm] Loaded EEPROM params in RAM\n");
// mavlink_missionlib_send_gcs_string("[pm] OK loading %s", param_get_default_file());
// result = MAV_RESULT_ACCEPTED;
// } else if (read_ret == 1) {
// mavlink_missionlib_send_gcs_string("[pm] OK no changes %s", param_get_default_file());
// result = MAV_RESULT_ACCEPTED;
// } else {
// if (read_ret < -1) {
// mavlink_missionlib_send_gcs_string("[pm] ERR loading %s", param_get_default_file());
// } else {
// mavlink_missionlib_send_gcs_string("[pm] ERR no file %s", param_get_default_file());
// }
// result = MAV_RESULT_FAILED;
// }
// } else if (((int)(cmd_mavlink.param1)) == 1) {
// /* write all parameters from RAM to EEPROM */
// int write_ret = param_save_default();
// if (write_ret == OK) {
// mavlink_missionlib_send_gcs_string("[pm] OK saved %s", param_get_default_file());
// result = MAV_RESULT_ACCEPTED;
// } else {
// if (write_ret < -1) {
// mavlink_missionlib_send_gcs_string("[pm] ERR writing %s", param_get_default_file());
// } else {
// mavlink_missionlib_send_gcs_string("[pm] ERR writing %s", param_get_default_file());
// }
// result = MAV_RESULT_FAILED;
// }
// } else {
// //fprintf(stderr, "[mavlink pm] refusing unsupported storage request\n");
// mavlink_missionlib_send_gcs_string("[pm] refusing unsupp. STOR request");
// result = MAV_RESULT_UNSUPPORTED;
// }
// }
// }
// /* send back command result */
// //mavlink_msg_command_ack_send(chan, cmd.command, result);
// } break;
}
}

23
apps/mavlink/orb_listener.c

@ -114,6 +114,7 @@ static void l_manual_control_setpoint(struct listener *l); @@ -114,6 +114,7 @@ static void l_manual_control_setpoint(struct listener *l);
static void l_vehicle_attitude_controls(struct listener *l);
static void l_debug_key_value(struct listener *l);
static void l_optical_flow(struct listener *l);
static void l_vehicle_rates_setpoint(struct listener *l);
struct listener listeners[] = {
{l_sensor_combined, &mavlink_subs.sensor_sub, 0},
@ -136,6 +137,7 @@ struct listener listeners[] = { @@ -136,6 +137,7 @@ struct listener listeners[] = {
{l_vehicle_attitude_controls, &mavlink_subs.actuators_sub, 0},
{l_debug_key_value, &mavlink_subs.debug_key_value, 0},
{l_optical_flow, &mavlink_subs.optical_flow, 0},
{l_vehicle_rates_setpoint, &mavlink_subs.rates_setpoint_sub, 0},
};
static const unsigned n_listeners = sizeof(listeners) / sizeof(listeners[0]);
@ -408,6 +410,23 @@ l_attitude_setpoint(struct listener *l) @@ -408,6 +410,23 @@ l_attitude_setpoint(struct listener *l)
att_sp.thrust);
}
void
l_vehicle_rates_setpoint(struct listener *l)
{
struct vehicle_rates_setpoint_s rates_sp;
/* copy local position data into local buffer */
orb_copy(ORB_ID(vehicle_rates_setpoint), mavlink_subs.rates_setpoint_sub, &rates_sp);
if (gcs_link)
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(MAVLINK_COMM_0,
rates_sp.timestamp/1000,
rates_sp.roll,
rates_sp.pitch,
rates_sp.yaw,
rates_sp.thrust);
}
void
l_actuator_outputs(struct listener *l)
{
@ -695,6 +714,10 @@ uorb_receive_start(void) @@ -695,6 +714,10 @@ uorb_receive_start(void)
mavlink_subs.spa_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
orb_set_interval(mavlink_subs.spa_sub, 2000); /* 0.5 Hz updates */
/* --- RATES SETPOINT VALUE --- */
mavlink_subs.rates_setpoint_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
orb_set_interval(mavlink_subs.rates_setpoint_sub, 2000); /* 0.5 Hz updates */
/* --- ACTUATOR OUTPUTS --- */
mavlink_subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0));
mavlink_subs.act_1_sub = orb_subscribe(ORB_ID(actuator_outputs_1));

2
apps/mavlink/orb_topics.h

@ -52,6 +52,7 @@ @@ -52,6 +52,7 @@
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
@ -78,6 +79,7 @@ struct mavlink_subscriptions { @@ -78,6 +79,7 @@ struct mavlink_subscriptions {
int debug_key_value;
int input_rc_sub;
int optical_flow;
int rates_setpoint_sub;
};
extern struct mavlink_subscriptions mavlink_subs;

6
mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h

File diff suppressed because one or more lines are too long

2
mavlink/include/mavlink/v1.0/ardupilotmega/version.h

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:36:48 2012"
#define MAVLINK_BUILD_DATE "Mon Nov 26 18:29:46 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

8
mavlink/include/mavlink/v1.0/common/common.h

File diff suppressed because one or more lines are too long

276
mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h

@ -0,0 +1,276 @@ @@ -0,0 +1,276 @@
// MESSAGE MANUAL_SETPOINT PACKING
#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81
typedef struct __mavlink_manual_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll; ///< Desired roll rate in radians per second
float pitch; ///< Desired pitch rate in radians per second
float yaw; ///< Desired yaw rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1
uint8_t mode_switch; ///< Flight mode switch position, 0.. 255
uint8_t manual_override_switch; ///< Override mode switch position, 0.. 255
} mavlink_manual_setpoint_t;
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22
#define MAVLINK_MSG_ID_81_LEN 22
#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \
"MANUAL_SETPOINT", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \
{ "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \
{ "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \
} \
}
/**
* @brief Pack a manual_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_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 22, 106);
}
/**
* @brief Pack a manual_setpoint message on a channel
* @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_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 106);
}
/**
* @brief Encode a manual_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 manual_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint)
{
return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
}
/**
* @brief Send a manual_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, 22, 106);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, 22, 106);
#endif
}
#endif
// MESSAGE MANUAL_SETPOINT UNPACKING
/**
* @brief Get field time_boot_ms from manual_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll from manual_setpoint message
*
* @return Desired roll rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch from manual_setpoint message
*
* @return Desired pitch rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw from manual_setpoint message
*
* @return Desired yaw rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field thrust from manual_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field mode_switch from manual_setpoint message
*
* @return Flight mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field manual_override_switch from manual_setpoint message
*
* @return Override mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Decode a manual_setpoint message into a struct
*
* @param msg The message to decode
* @param manual_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg);
manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg);
manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg);
manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg);
manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg);
manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg);
manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg);
#else
memcpy(manual_setpoint, _MAV_PAYLOAD(msg), 22);
#endif
}

232
mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h

@ -0,0 +1,232 @@ @@ -0,0 +1,232 @@
// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT PACKING
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80
typedef struct __mavlink_roll_pitch_yaw_rates_thrust_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll_rate; ///< Desired roll rate in radians per second
float pitch_rate; ///< Desired pitch rate in radians per second
float yaw_rate; ///< Desired yaw rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_rates_thrust_setpoint_t;
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20
#define MAVLINK_MSG_ID_80_LEN 20
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_RATES_THRUST_SETPOINT", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, time_boot_ms) }, \
{ "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, roll_rate) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, yaw_rate) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, thrust) }, \
} \
}
/**
* @brief Pack a roll_pitch_yaw_rates_thrust_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_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 20, 127);
}
/**
* @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message on a channel
* @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_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll_rate,float pitch_rate,float yaw_rate,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 127);
}
/**
* @brief Encode a roll_pitch_yaw_rates_thrust_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_rates_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust);
}
/**
* @brief Send a roll_pitch_yaw_rates_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, 20, 127);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, 20, 127);
#endif
}
#endif
// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT UNPACKING
/**
* @brief Get field time_boot_ms from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired roll rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired pitch rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired yaw rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field thrust from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a roll_pitch_yaw_rates_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_rates_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(msg);
roll_pitch_yaw_rates_thrust_setpoint->roll_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->pitch_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->yaw_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), 20);
#endif
}

108
mavlink/include/mavlink/v1.0/common/testsuite.h

@ -3178,6 +3178,112 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma @@ -3178,6 +3178,112 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
};
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll_rate = packet_in.roll_rate;
packet1.pitch_rate = packet_in.pitch_rate;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.thrust = packet_in.thrust;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
65,
132,
};
mavlink_manual_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
packet1.mode_switch = packet_in.mode_switch;
packet1.manual_override_switch = packet_in.manual_override_switch;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_manual_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -4301,6 +4407,8 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink @@ -4301,6 +4407,8 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vfr_hud(system_id, component_id, last_msg);
mavlink_test_command_long(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_manual_setpoint(system_id, component_id, last_msg);
mavlink_test_local_position_ned_system_global_offset(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg);

2
mavlink/include/mavlink/v1.0/common/version.h

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:22 2012"
#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

6
mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h

File diff suppressed because one or more lines are too long

2
mavlink/include/mavlink/v1.0/matrixpilot/version.h

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:22 2012"
#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:03 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

6
mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h

File diff suppressed because one or more lines are too long

2
mavlink/include/mavlink/v1.0/pixhawk/version.h

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:02 2012"
#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:17 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

6
mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h

File diff suppressed because one or more lines are too long

2
mavlink/include/mavlink/v1.0/sensesoar/version.h

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:13 2012"
#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

Loading…
Cancel
Save