mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
MAVLink: added missing files from recent update
thanks to Randy for spotting this git-svn-id: https://arducopter.googlecode.com/svn/trunk@3086 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
1989497ae9
commit
5ffd66bc83
3
libraries/GCS_MAVLink/.gitignore
vendored
Normal file
3
libraries/GCS_MAVLink/.gitignore
vendored
Normal file
@ -0,0 +1,3 @@
|
||||
*~
|
||||
doc/html
|
||||
doc/*.log
|
@ -0,0 +1,342 @@
|
||||
// MESSAGE SENSOR_OFFSETS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
|
||||
|
||||
typedef struct __mavlink_sensor_offsets_t
|
||||
{
|
||||
int16_t mag_ofs_x; ///< magnetometer X offset
|
||||
int16_t mag_ofs_y; ///< magnetometer Y offset
|
||||
int16_t mag_ofs_z; ///< magnetometer Z offset
|
||||
float mag_declination; ///< magnetic declination (radians)
|
||||
int32_t raw_press; ///< raw pressure from barometer
|
||||
int32_t raw_temp; ///< raw temperature from barometer
|
||||
float gyro_cal_x; ///< gyro X calibration
|
||||
float gyro_cal_y; ///< gyro Y calibration
|
||||
float gyro_cal_z; ///< gyro Z calibration
|
||||
float accel_cal_x; ///< accel X calibration
|
||||
float accel_cal_y; ///< accel Y calibration
|
||||
float accel_cal_z; ///< accel Z calibration
|
||||
|
||||
} mavlink_sensor_offsets_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a sensor_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 mag_ofs_x magnetometer X offset
|
||||
* @param mag_ofs_y magnetometer Y offset
|
||||
* @param mag_ofs_z magnetometer Z offset
|
||||
* @param mag_declination magnetic declination (radians)
|
||||
* @param raw_press raw pressure from barometer
|
||||
* @param raw_temp raw temperature from barometer
|
||||
* @param gyro_cal_x gyro X calibration
|
||||
* @param gyro_cal_y gyro Y calibration
|
||||
* @param gyro_cal_z gyro Z calibration
|
||||
* @param accel_cal_x accel X calibration
|
||||
* @param accel_cal_y accel Y calibration
|
||||
* @param accel_cal_z accel Z calibration
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
|
||||
|
||||
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
|
||||
i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
|
||||
i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
|
||||
i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
|
||||
i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
|
||||
i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
|
||||
i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
|
||||
i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
|
||||
i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
|
||||
i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a sensor_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 mag_ofs_x magnetometer X offset
|
||||
* @param mag_ofs_y magnetometer Y offset
|
||||
* @param mag_ofs_z magnetometer Z offset
|
||||
* @param mag_declination magnetic declination (radians)
|
||||
* @param raw_press raw pressure from barometer
|
||||
* @param raw_temp raw temperature from barometer
|
||||
* @param gyro_cal_x gyro X calibration
|
||||
* @param gyro_cal_y gyro Y calibration
|
||||
* @param gyro_cal_z gyro Z calibration
|
||||
* @param accel_cal_x accel X calibration
|
||||
* @param accel_cal_y accel Y calibration
|
||||
* @param accel_cal_z accel Z calibration
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
|
||||
|
||||
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
|
||||
i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
|
||||
i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
|
||||
i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
|
||||
i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
|
||||
i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
|
||||
i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
|
||||
i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
|
||||
i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
|
||||
i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a sensor_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 sensor_offsets C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
|
||||
{
|
||||
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a sensor_offsets message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param mag_ofs_x magnetometer X offset
|
||||
* @param mag_ofs_y magnetometer Y offset
|
||||
* @param mag_ofs_z magnetometer Z offset
|
||||
* @param mag_declination magnetic declination (radians)
|
||||
* @param raw_press raw pressure from barometer
|
||||
* @param raw_temp raw temperature from barometer
|
||||
* @param gyro_cal_x gyro X calibration
|
||||
* @param gyro_cal_y gyro Y calibration
|
||||
* @param gyro_cal_z gyro Z calibration
|
||||
* @param accel_cal_x accel X calibration
|
||||
* @param accel_cal_y accel Y calibration
|
||||
* @param accel_cal_z accel Z calibration
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_sensor_offsets_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE SENSOR_OFFSETS UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field mag_ofs_x from sensor_offsets message
|
||||
*
|
||||
* @return magnetometer X offset
|
||||
*/
|
||||
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload)[0];
|
||||
r.b[0] = (msg->payload)[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field mag_ofs_y from sensor_offsets message
|
||||
*
|
||||
* @return magnetometer Y offset
|
||||
*/
|
||||
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field mag_ofs_z from sensor_offsets message
|
||||
*
|
||||
* @return magnetometer Z offset
|
||||
*/
|
||||
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field mag_declination from sensor_offsets message
|
||||
*
|
||||
* @return magnetic declination (radians)
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field raw_press from sensor_offsets message
|
||||
*
|
||||
* @return raw pressure from barometer
|
||||
*/
|
||||
static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[3];
|
||||
return (int32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field raw_temp from sensor_offsets message
|
||||
*
|
||||
* @return raw temperature from barometer
|
||||
*/
|
||||
static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[3];
|
||||
return (int32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field gyro_cal_x from sensor_offsets message
|
||||
*
|
||||
* @return gyro X calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field gyro_cal_y from sensor_offsets message
|
||||
*
|
||||
* @return gyro Y calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field gyro_cal_z from sensor_offsets message
|
||||
*
|
||||
* @return gyro Z calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field accel_cal_x from sensor_offsets message
|
||||
*
|
||||
* @return accel X calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field accel_cal_y from sensor_offsets message
|
||||
*
|
||||
* @return accel Y calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field accel_cal_z from sensor_offsets message
|
||||
*
|
||||
* @return accel Z calibration
|
||||
*/
|
||||
static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a sensor_offsets message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param sensor_offsets C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
|
||||
{
|
||||
sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
|
||||
sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
|
||||
sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
|
||||
sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
|
||||
sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
|
||||
sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
|
||||
sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
|
||||
sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
|
||||
sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
|
||||
sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
|
||||
sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
|
||||
sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
|
||||
}
|
232
libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h
Normal file
232
libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h
Normal file
@ -0,0 +1,232 @@
|
||||
// MESSAGE HIL_CONTROLS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_CONTROLS 68
|
||||
|
||||
typedef struct __mavlink_hil_controls_t
|
||||
{
|
||||
uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
float roll_ailerons; ///< Control output -3 .. 1
|
||||
float pitch_elevator; ///< Control output -1 .. 1
|
||||
float yaw_rudder; ///< Control output -1 .. 1
|
||||
float throttle; ///< Throttle 0 .. 1
|
||||
uint8_t mode; ///< System mode (MAV_MODE)
|
||||
uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
|
||||
|
||||
} mavlink_hil_controls_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a hil_controls 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_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll_ailerons Control output -3 .. 1
|
||||
* @param pitch_elevator Control output -1 .. 1
|
||||
* @param yaw_rudder Control output -1 .. 1
|
||||
* @param throttle Throttle 0 .. 1
|
||||
* @param mode System mode (MAV_MODE)
|
||||
* @param nav_mode Navigation mode (MAV_NAV_MODE)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
|
||||
|
||||
i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
|
||||
i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
|
||||
i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
|
||||
i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
|
||||
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
|
||||
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a hil_controls 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_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll_ailerons Control output -3 .. 1
|
||||
* @param pitch_elevator Control output -1 .. 1
|
||||
* @param yaw_rudder Control output -1 .. 1
|
||||
* @param throttle Throttle 0 .. 1
|
||||
* @param mode System mode (MAV_MODE)
|
||||
* @param nav_mode Navigation mode (MAV_NAV_MODE)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
|
||||
|
||||
i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
|
||||
i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
|
||||
i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
|
||||
i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
|
||||
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
|
||||
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a hil_controls 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 hil_controls C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
|
||||
{
|
||||
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->mode, hil_controls->nav_mode);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a hil_controls message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll_ailerons Control output -3 .. 1
|
||||
* @param pitch_elevator Control output -1 .. 1
|
||||
* @param yaw_rudder Control output -1 .. 1
|
||||
* @param throttle Throttle 0 .. 1
|
||||
* @param mode System mode (MAV_MODE)
|
||||
* @param nav_mode Navigation mode (MAV_NAV_MODE)
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_hil_controls_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE HIL_CONTROLS UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field time_us from hil_controls message
|
||||
*
|
||||
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_64bit r;
|
||||
r.b[7] = (msg->payload)[0];
|
||||
r.b[6] = (msg->payload)[1];
|
||||
r.b[5] = (msg->payload)[2];
|
||||
r.b[4] = (msg->payload)[3];
|
||||
r.b[3] = (msg->payload)[4];
|
||||
r.b[2] = (msg->payload)[5];
|
||||
r.b[1] = (msg->payload)[6];
|
||||
r.b[0] = (msg->payload)[7];
|
||||
return (uint64_t)r.ll;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll_ailerons from hil_controls message
|
||||
*
|
||||
* @return Control output -3 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch_elevator from hil_controls message
|
||||
*
|
||||
* @return Control output -1 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw_rudder from hil_controls message
|
||||
*
|
||||
* @return Control output -1 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field throttle from hil_controls message
|
||||
*
|
||||
* @return Throttle 0 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field mode from hil_controls message
|
||||
*
|
||||
* @return System mode (MAV_MODE)
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field nav_mode from hil_controls message
|
||||
*
|
||||
* @return Navigation mode (MAV_NAV_MODE)
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a hil_controls message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param hil_controls C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
|
||||
{
|
||||
hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
|
||||
hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
|
||||
hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
|
||||
hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
|
||||
hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
|
||||
hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
|
||||
hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
|
||||
}
|
428
libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h
Normal file
428
libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h
Normal file
@ -0,0 +1,428 @@
|
||||
// MESSAGE HIL_STATE PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_STATE 67
|
||||
|
||||
typedef struct __mavlink_hil_state_t
|
||||
{
|
||||
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
float roll; ///< Roll angle (rad)
|
||||
float pitch; ///< Pitch angle (rad)
|
||||
float yaw; ///< Yaw angle (rad)
|
||||
float rollspeed; ///< Roll angular speed (rad/s)
|
||||
float pitchspeed; ///< Pitch angular speed (rad/s)
|
||||
float yawspeed; ///< Yaw angular speed (rad/s)
|
||||
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
|
||||
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
int16_t xacc; ///< X acceleration (mg)
|
||||
int16_t yacc; ///< Y acceleration (mg)
|
||||
int16_t zacc; ///< Z acceleration (mg)
|
||||
|
||||
} mavlink_hil_state_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a hil_state 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param rollspeed Roll angular speed (rad/s)
|
||||
* @param pitchspeed Pitch angular speed (rad/s)
|
||||
* @param yawspeed Yaw angular speed (rad/s)
|
||||
* @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
|
||||
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
* @param xacc X acceleration (mg)
|
||||
* @param yacc Y acceleration (mg)
|
||||
* @param zacc Z acceleration (mg)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
|
||||
i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
|
||||
i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
|
||||
i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
|
||||
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
|
||||
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
|
||||
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
|
||||
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a hil_state 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param rollspeed Roll angular speed (rad/s)
|
||||
* @param pitchspeed Pitch angular speed (rad/s)
|
||||
* @param yawspeed Yaw angular speed (rad/s)
|
||||
* @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
|
||||
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
* @param xacc X acceleration (mg)
|
||||
* @param yacc Y acceleration (mg)
|
||||
* @param zacc Z acceleration (mg)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
|
||||
i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
|
||||
i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
|
||||
i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
|
||||
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
|
||||
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
|
||||
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
|
||||
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a hil_state 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 hil_state C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
|
||||
{
|
||||
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a hil_state message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param rollspeed Roll angular speed (rad/s)
|
||||
* @param pitchspeed Pitch angular speed (rad/s)
|
||||
* @param yawspeed Yaw angular speed (rad/s)
|
||||
* @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
|
||||
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
* @param xacc X acceleration (mg)
|
||||
* @param yacc Y acceleration (mg)
|
||||
* @param zacc Z acceleration (mg)
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_hil_state_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE HIL_STATE UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field usec from hil_state message
|
||||
*
|
||||
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_hil_state_get_usec(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_64bit r;
|
||||
r.b[7] = (msg->payload)[0];
|
||||
r.b[6] = (msg->payload)[1];
|
||||
r.b[5] = (msg->payload)[2];
|
||||
r.b[4] = (msg->payload)[3];
|
||||
r.b[3] = (msg->payload)[4];
|
||||
r.b[2] = (msg->payload)[5];
|
||||
r.b[1] = (msg->payload)[6];
|
||||
r.b[0] = (msg->payload)[7];
|
||||
return (uint64_t)r.ll;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll from hil_state message
|
||||
*
|
||||
* @return Roll angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch from hil_state message
|
||||
*
|
||||
* @return Pitch angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw from hil_state message
|
||||
*
|
||||
* @return Yaw angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field rollspeed from hil_state message
|
||||
*
|
||||
* @return Roll angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitchspeed from hil_state message
|
||||
*
|
||||
* @return Pitch angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yawspeed from hil_state message
|
||||
*
|
||||
* @return Yaw angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lat from hil_state message
|
||||
*
|
||||
* @return Latitude, expressed as * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (int32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lon from hil_state message
|
||||
*
|
||||
* @return Longitude, expressed as * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3];
|
||||
return (int32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field alt from hil_state message
|
||||
*
|
||||
* @return Altitude in meters, expressed as * 1000 (millimeters)
|
||||
*/
|
||||
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
|
||||
return (int32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vx from hil_state message
|
||||
*
|
||||
* @return Ground X Speed (Latitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vy from hil_state message
|
||||
*
|
||||
* @return Ground Y Speed (Longitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vz from hil_state message
|
||||
*
|
||||
* @return Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field xacc from hil_state message
|
||||
*
|
||||
* @return X acceleration (mg)
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yacc from hil_state message
|
||||
*
|
||||
* @return Y acceleration (mg)
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field zacc from hil_state message
|
||||
*
|
||||
* @return Z acceleration (mg)
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_16bit r;
|
||||
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
|
||||
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
|
||||
return (int16_t)r.s;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a hil_state message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param hil_state C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
|
||||
{
|
||||
hil_state->usec = mavlink_msg_hil_state_get_usec(msg);
|
||||
hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
|
||||
hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
|
||||
hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
|
||||
hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
|
||||
hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
|
||||
hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
|
||||
hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
|
||||
hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
|
||||
hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
|
||||
hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
|
||||
hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
|
||||
hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
|
||||
hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
|
||||
hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
|
||||
hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
|
||||
}
|
@ -0,0 +1,194 @@
|
||||
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 58
|
||||
|
||||
typedef struct __mavlink_roll_pitch_yaw_speed_thrust_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
|
||||
float thrust; ///< Collective thrust, normalized to 0 .. 1
|
||||
|
||||
} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a roll_pitch_yaw_speed_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_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
|
||||
* @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_speed_thrust_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, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
|
||||
|
||||
i += put_uint32_t_by_index(time_ms, i, msg->payload); // Timestamp in milliseconds since system boot
|
||||
i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
|
||||
i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
|
||||
i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a roll_pitch_yaw_speed_thrust_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
|
||||
* @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_speed_thrust_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, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
|
||||
|
||||
i += put_uint32_t_by_index(time_ms, i, msg->payload); // Timestamp in milliseconds since system boot
|
||||
i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
|
||||
i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
|
||||
i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a roll_pitch_yaw_speed_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_speed_thrust_setpoint C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
|
||||
{
|
||||
return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a roll_pitch_yaw_speed_thrust_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
|
||||
* @param thrust Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_ms, roll_speed, pitch_speed, yaw_speed, thrust);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field time_ms from roll_pitch_yaw_speed_thrust_setpoint message
|
||||
*
|
||||
* @return Timestamp in milliseconds since system boot
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_ms(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 (uint32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message
|
||||
*
|
||||
* @return Desired roll angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message
|
||||
*
|
||||
* @return Desired pitch angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message
|
||||
*
|
||||
* @return Desired yaw angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message
|
||||
*
|
||||
* @return Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
|
||||
{
|
||||
roll_pitch_yaw_speed_thrust_setpoint->time_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_ms(msg);
|
||||
roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg);
|
||||
roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg);
|
||||
roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg);
|
||||
roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg);
|
||||
}
|
@ -0,0 +1,194 @@
|
||||
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 57
|
||||
|
||||
typedef struct __mavlink_roll_pitch_yaw_thrust_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
|
||||
float thrust; ///< Collective thrust, normalized to 0 .. 1
|
||||
|
||||
} mavlink_roll_pitch_yaw_thrust_setpoint_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a roll_pitch_yaw_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_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
|
||||
* @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_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t time_ms, float roll, float pitch, float yaw, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
|
||||
|
||||
i += put_uint32_t_by_index(time_ms, i, msg->payload); // Timestamp in milliseconds since system boot
|
||||
i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a roll_pitch_yaw_thrust_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
|
||||
* @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_thrust_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, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
|
||||
|
||||
i += put_uint32_t_by_index(time_ms, i, msg->payload); // Timestamp in milliseconds since system boot
|
||||
i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a roll_pitch_yaw_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_thrust_setpoint C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
|
||||
{
|
||||
return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a roll_pitch_yaw_thrust_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
|
||||
* @param thrust Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_ms, float roll, float pitch, float yaw, float thrust)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_ms, roll, pitch, yaw, thrust);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field time_ms from roll_pitch_yaw_thrust_setpoint message
|
||||
*
|
||||
* @return Timestamp in milliseconds since system boot
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_ms(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 (uint32_t)r.i;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll from roll_pitch_yaw_thrust_setpoint message
|
||||
*
|
||||
* @return Desired roll angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message
|
||||
*
|
||||
* @return Desired pitch angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message
|
||||
*
|
||||
* @return Desired yaw angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message
|
||||
*
|
||||
* @return Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
|
||||
{
|
||||
roll_pitch_yaw_thrust_setpoint->time_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_ms(msg);
|
||||
roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg);
|
||||
roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg);
|
||||
roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg);
|
||||
roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg);
|
||||
}
|
@ -0,0 +1,206 @@
|
||||
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 56
|
||||
|
||||
typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
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
|
||||
float thrust; ///< Collective thrust, normalized to 0 .. 1
|
||||
|
||||
} mavlink_set_roll_pitch_yaw_speed_thrust_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a set_roll_pitch_yaw_speed_thrust 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 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
|
||||
* @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_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
|
||||
|
||||
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_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
|
||||
i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
|
||||
i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a set_roll_pitch_yaw_speed_thrust 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 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
|
||||
* @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_set_roll_pitch_yaw_speed_thrust_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, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
|
||||
|
||||
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_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s
|
||||
i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s
|
||||
i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a set_roll_pitch_yaw_speed_thrust 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_roll_pitch_yaw_speed_thrust C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
|
||||
{
|
||||
return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a set_roll_pitch_yaw_speed_thrust message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @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
|
||||
* @param thrust Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload)[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return Component ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return Desired roll angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return Desired pitch angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return Desired yaw angular speed in rad/s
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message
|
||||
*
|
||||
* @return Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
|
||||
{
|
||||
set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg);
|
||||
set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg);
|
||||
set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg);
|
||||
set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg);
|
||||
set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg);
|
||||
set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg);
|
||||
}
|
@ -0,0 +1,206 @@
|
||||
// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 55
|
||||
|
||||
typedef struct __mavlink_set_roll_pitch_yaw_thrust_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
float roll; ///< Desired roll angle in radians
|
||||
float pitch; ///< Desired pitch angle in radians
|
||||
float yaw; ///< Desired yaw angle in radians
|
||||
float thrust; ///< Collective thrust, normalized to 0 .. 1
|
||||
|
||||
} mavlink_set_roll_pitch_yaw_thrust_t;
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a set_roll_pitch_yaw_thrust 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 roll Desired roll angle in radians
|
||||
* @param pitch Desired pitch angle in radians
|
||||
* @param yaw Desired yaw angle in radians
|
||||
* @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_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
|
||||
|
||||
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_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a set_roll_pitch_yaw_thrust 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 roll Desired roll angle in radians
|
||||
* @param pitch Desired pitch angle in radians
|
||||
* @param yaw Desired yaw angle in radians
|
||||
* @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_set_roll_pitch_yaw_thrust_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, float roll, float pitch, float yaw, float thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
|
||||
|
||||
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_float_by_index(roll, i, msg->payload); // Desired roll angle in radians
|
||||
i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians
|
||||
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians
|
||||
i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a set_roll_pitch_yaw_thrust 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_roll_pitch_yaw_thrust C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
|
||||
{
|
||||
return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a set_roll_pitch_yaw_thrust message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param roll Desired roll angle in radians
|
||||
* @param pitch Desired pitch angle in radians
|
||||
* @param yaw Desired yaw angle in radians
|
||||
* @param thrust Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll, pitch, yaw, thrust);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
#endif
|
||||
// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload)[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_component from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return Component ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field roll from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return Desired roll angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return Desired pitch angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return Desired yaw angle in radians
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field thrust from set_roll_pitch_yaw_thrust message
|
||||
*
|
||||
* @return Collective thrust, normalized to 0 .. 1
|
||||
*/
|
||||
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg)
|
||||
{
|
||||
generic_32bit r;
|
||||
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
|
||||
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
|
||||
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
|
||||
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
|
||||
return (float)r.f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a set_roll_pitch_yaw_thrust message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
|
||||
{
|
||||
set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg);
|
||||
set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg);
|
||||
set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg);
|
||||
set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg);
|
||||
set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg);
|
||||
set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg);
|
||||
}
|
2
libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/.gitignore
vendored
Normal file
2
libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
||||
*.mode1v3
|
||||
*.pbxuser
|
Loading…
Reference in New Issue
Block a user