mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
Updated mavlink to latest dev branch version.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1015 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
665dbefbd4
commit
a37d1ddb91
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, November 14 2010, 16:32 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef ARDUPILOTMEGA_H
|
||||
#define ARDUPILOTMEGA_H
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, November 14 2010, 16:32 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Friday, November 26 2010, 06:53 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef COMMON_H
|
||||
#define COMMON_H
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Friday, November 26 2010, 06:53 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t compon
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ACTION;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system executing the action
|
||||
i += put_uint8_t_by_index(target_component, i, msg->payload); //The component executing the action
|
||||
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action)
|
||||
{
|
||||
return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t comp
|
||||
static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_action_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, target_component, action);
|
||||
mavlink_msg_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, target_component, action);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t action, uint8_t result)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
|
||||
|
||||
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
|
||||
i += put_uint8_t_by_index(result, i, msg->payload); //0: Action DENIED, 1: Action executed
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack)
|
||||
{
|
||||
return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_action_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, action, result);
|
||||
mavlink_msg_action_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, action, result);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_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)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds)
|
||||
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)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
|
||||
{
|
||||
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
|
||||
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_attitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed);
|
||||
mavlink_msg_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -38,6 +38,20 @@ static inline uint16_t mavlink_msg_attitude_controller_output_pack(uint8_t syste
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT;
|
||||
|
||||
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
|
||||
i += put_int8_t_by_index(roll, i, msg->payload); //Attitude roll: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(pitch, i, msg->payload); //Attitude pitch: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(yaw, i, msg->payload); //Attitude yaw: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(thrust, i, msg->payload); //Attitude thrust: -128: -100%, 127: +100%
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_controller_output_t* attitude_controller_output)
|
||||
{
|
||||
return mavlink_msg_attitude_controller_output_pack(system_id, component_id, msg, attitude_controller_output->enabled, attitude_controller_output->roll, attitude_controller_output->pitch, attitude_controller_output->yaw, attitude_controller_output->thrust);
|
||||
@ -48,7 +62,7 @@ static inline uint16_t mavlink_msg_attitude_controller_output_encode(uint8_t sys
|
||||
static inline void mavlink_msg_attitude_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_attitude_controller_output_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled, roll, pitch, yaw, thrust);
|
||||
mavlink_msg_attitude_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled, roll, pitch, yaw, thrust);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -26,6 +26,16 @@ static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t componen
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t version)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_BOOT;
|
||||
|
||||
i += put_uint32_t_by_index(version, i, msg->payload); //The onboard software version
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot)
|
||||
{
|
||||
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
|
||||
@ -36,7 +46,7 @@ static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t compon
|
||||
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_boot_pack(mavlink_system.sysid, mavlink_system.compid, &msg, version);
|
||||
mavlink_msg_boot_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, version);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_DEBUG;
|
||||
|
||||
i += put_uint8_t_by_index(ind, i, msg->payload); //index of debug variable
|
||||
i += put_float_by_index(value, i, msg->payload); //DEBUG value
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
|
||||
{
|
||||
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
|
||||
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_debug_pack(mavlink_system.sysid, mavlink_system.compid, &msg, ind, value);
|
||||
mavlink_msg_debug_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, ind, value);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
|
||||
i += put_float_by_index(lat, i, msg->payload); //X Position
|
||||
i += put_float_by_index(lon, i, msg->payload); //Y Position
|
||||
i += put_float_by_index(alt, i, msg->payload); //Z Position
|
||||
i += put_float_by_index(vx, i, msg->payload); //X Speed
|
||||
i += put_float_by_index(vy, i, msg->payload); //Y Speed
|
||||
i += put_float_by_index(vz, i, msg->payload); //Z Speed
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
|
||||
{
|
||||
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_global_position_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, lat, lon, alt, vx, vy, vz);
|
||||
mavlink_msg_global_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, lat, lon, alt, vx, vy, vz);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
|
||||
i += put_uint8_t_by_index(fix_type, i, msg->payload); //0-1: no fix, 2: 2D fix, 3: 3D fix
|
||||
i += put_float_by_index(lat, i, msg->payload); //X Position
|
||||
i += put_float_by_index(lon, i, msg->payload); //Y Position
|
||||
i += put_float_by_index(alt, i, msg->payload); //Z Position in meters
|
||||
i += put_float_by_index(eph, i, msg->payload); //Uncertainty in meters of latitude
|
||||
i += put_float_by_index(epv, i, msg->payload); //Uncertainty in meters of longitude
|
||||
i += put_float_by_index(v, i, msg->payload); //Overall speed
|
||||
i += put_float_by_index(hdg, i, msg->payload); //Heading, in FIXME
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
|
||||
{
|
||||
return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t com
|
||||
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_gps_raw_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
|
||||
mavlink_msg_gps_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -46,6 +46,21 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
|
||||
|
||||
i += put_uint8_t_by_index(satellites_visible, i, msg->payload); //Number of satellites visible
|
||||
i += put_array_by_index(satellite_prn, 20, i, msg->payload); //Global satellite ID
|
||||
i += put_array_by_index(satellite_used, 20, i, msg->payload); //0: Satellite not used, 1: used for localization
|
||||
i += put_array_by_index(satellite_elevation, 20, i, msg->payload); //Elevation (0: right on top of receiver, 90: on the horizon) of satellite
|
||||
i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); //Direction of satellite, 0: 0 deg, 255: 360 deg.
|
||||
i += put_array_by_index(satellite_snr, 20, i, msg->payload); //Signal to noise ratio of satellite
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
|
||||
{
|
||||
return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
|
||||
@ -56,7 +71,7 @@ static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_gps_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr);
|
||||
mavlink_msg_gps_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
|
||||
|
||||
i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
|
||||
i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
|
||||
{
|
||||
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c
|
||||
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, type, autopilot);
|
||||
mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
|
||||
i += put_float_by_index(x, i, msg->payload); //X Position
|
||||
i += put_float_by_index(y, i, msg->payload); //Y Position
|
||||
i += put_float_by_index(z, i, msg->payload); //Z Position
|
||||
i += put_float_by_index(vx, i, msg->payload); //X Speed
|
||||
i += put_float_by_index(vy, i, msg->payload); //Y Speed
|
||||
i += put_float_by_index(vz, i, msg->payload); //Z Speed
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position)
|
||||
{
|
||||
return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint
|
||||
static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_local_position_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, vx, vy, vz);
|
||||
mavlink_msg_local_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, vx, vy, vz);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
|
||||
|
||||
i += put_float_by_index(x, i, msg->payload); //x position 1
|
||||
i += put_float_by_index(y, i, msg->payload); //y position 1
|
||||
i += put_float_by_index(z, i, msg->payload); //z position 1
|
||||
i += put_float_by_index(yaw, i, msg->payload); //x position 2
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
|
||||
{
|
||||
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system
|
||||
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_local_position_setpoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, x, y, z, yaw);
|
||||
mavlink_msg_local_position_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_setpoint_set_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 x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
|
||||
|
||||
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(x, i, msg->payload); //x position 1
|
||||
i += put_float_by_index(y, i, msg->payload); //y position 1
|
||||
i += put_float_by_index(z, i, msg->payload); //z position 1
|
||||
i += put_float_by_index(yaw, i, msg->payload); //x position 2
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
|
||||
{
|
||||
return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t sy
|
||||
static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_local_position_setpoint_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, x, y, z, yaw);
|
||||
mavlink_msg_local_position_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
|
||||
i += put_float_by_index(roll, i, msg->payload); //roll
|
||||
i += put_float_by_index(pitch, i, msg->payload); //pitch
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw
|
||||
i += put_float_by_index(thrust, i, msg->payload); //thrust
|
||||
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
|
||||
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
|
||||
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
|
||||
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
|
||||
{
|
||||
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint
|
||||
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_manual_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
|
||||
mavlink_msg_manual_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_request_list_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)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
|
||||
|
||||
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
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
|
||||
{
|
||||
return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_request_list_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component);
|
||||
mavlink_msg_param_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -36,6 +36,19 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_request_read_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, const int8_t* param_id, uint16_t param_index)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
|
||||
|
||||
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_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
|
||||
i += put_uint16_t_by_index(param_index, i, msg->payload); //Parameter index
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
|
||||
{
|
||||
return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
|
||||
@ -46,7 +59,7 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, uint16_t param_index)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_request_read_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, param_id, param_index);
|
||||
mavlink_msg_param_request_read_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_index);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -36,6 +36,19 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_set_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, const int8_t* param_id, float param_value)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
|
||||
|
||||
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_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
|
||||
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
|
||||
{
|
||||
return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value);
|
||||
@ -46,7 +59,7 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c
|
||||
static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, param_id, param_value);
|
||||
mavlink_msg_param_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_value);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -36,6 +36,19 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
|
||||
|
||||
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
|
||||
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
|
||||
i += put_uint16_t_by_index(param_count, i, msg->payload); //Total number of onboard parameters
|
||||
i += put_uint16_t_by_index(param_index, i, msg->payload); //Index of this onboard parameter
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
|
||||
{
|
||||
return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index);
|
||||
@ -46,7 +59,7 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_value_pack(mavlink_system.sysid, mavlink_system.compid, &msg, param_id, param_value, param_count, param_index);
|
||||
mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, param_id, param_value, param_count, param_index);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PING;
|
||||
|
||||
i += put_uint32_t_by_index(seq, i, msg->payload); //PING sequence
|
||||
i += put_uint8_t_by_index(target_system, i, msg->payload); //0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
|
||||
i += put_uint8_t_by_index(target_component, i, msg->payload); //0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
|
||||
i += put_uint64_t_by_index(time, i, msg->payload); //Unix timestamp in microseconds
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
|
||||
{
|
||||
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t compon
|
||||
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_ping_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq, target_system, target_component, time);
|
||||
mavlink_msg_ping_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq, target_system, target_component, time);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -38,6 +38,20 @@ static inline uint16_t mavlink_msg_position_controller_output_pack(uint8_t syste
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT;
|
||||
|
||||
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
|
||||
i += put_int8_t_by_index(x, i, msg->payload); //Position x: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(y, i, msg->payload); //Position y: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(z, i, msg->payload); //Position z: -128: -100%, 127: +100%
|
||||
i += put_int8_t_by_index(yaw, i, msg->payload); //Position yaw: -128: -100%, 127: +100%
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_controller_output_t* position_controller_output)
|
||||
{
|
||||
return mavlink_msg_position_controller_output_pack(system_id, component_id, msg, position_controller_output->enabled, position_controller_output->x, position_controller_output->y, position_controller_output->z, position_controller_output->yaw);
|
||||
@ -48,7 +62,7 @@ static inline uint16_t mavlink_msg_position_controller_output_encode(uint8_t sys
|
||||
static inline void mavlink_msg_position_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_position_controller_output_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled, x, y, z, yaw);
|
||||
mavlink_msg_position_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
|
||||
|
||||
i += put_float_by_index(x, i, msg->payload); //x position
|
||||
i += put_float_by_index(y, i, msg->payload); //y position
|
||||
i += put_float_by_index(z, i, msg->payload); //z position
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
|
||||
{
|
||||
return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_position_target_pack(mavlink_system.sysid, mavlink_system.compid, &msg, x, y, z, yaw);
|
||||
mavlink_msg_position_target_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -53,6 +53,25 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
|
||||
i += put_int16_t_by_index(xacc, i, msg->payload); //X acceleration (mg raw)
|
||||
i += put_int16_t_by_index(yacc, i, msg->payload); //Y acceleration (mg raw)
|
||||
i += put_int16_t_by_index(zacc, i, msg->payload); //Z acceleration (mg raw)
|
||||
i += put_int16_t_by_index(xgyro, i, msg->payload); //Angular speed around X axis (millirad /sec)
|
||||
i += put_int16_t_by_index(ygyro, i, msg->payload); //Angular speed around Y axis (millirad /sec)
|
||||
i += put_int16_t_by_index(zgyro, i, msg->payload); //Angular speed around Z axis (millirad /sec)
|
||||
i += put_int16_t_by_index(xmag, i, msg->payload); //X Magnetic field (milli tesla)
|
||||
i += put_int16_t_by_index(ymag, i, msg->payload); //Y Magnetic field (milli tesla)
|
||||
i += put_int16_t_by_index(zmag, i, msg->payload); //Z Magnetic field (milli tesla)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
|
||||
{
|
||||
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
|
||||
@ -63,7 +82,7 @@ static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t com
|
||||
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_raw_imu_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag);
|
||||
mavlink_msg_raw_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
|
||||
i += put_int32_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal)
|
||||
i += put_int32_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal)
|
||||
i += put_int32_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
|
||||
{
|
||||
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
|
||||
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_raw_pressure_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, press_abs, press_diff1, press_diff2);
|
||||
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
|
||||
|
||||
i += put_uint16_t_by_index(chan1_raw, i, msg->payload); //RC channel 1 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan2_raw, i, msg->payload); //RC channel 2 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan3_raw, i, msg->payload); //RC channel 3 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan4_raw, i, msg->payload); //RC channel 4 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan5_raw, i, msg->payload); //RC channel 5 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan6_raw, i, msg->payload); //RC channel 6 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan7_raw, i, msg->payload); //RC channel 7 value, in microseconds
|
||||
i += put_uint16_t_by_index(chan8_raw, i, msg->payload); //RC channel 8 value, in microseconds
|
||||
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
|
||||
{
|
||||
return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_rc_channels_raw_pack(mavlink_system.sysid, mavlink_system.compid, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi);
|
||||
mavlink_msg_rc_channels_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
|
||||
|
||||
i += put_int16_t_by_index(chan1_scaled, i, msg->payload); //RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan2_scaled, i, msg->payload); //RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan3_scaled, i, msg->payload); //RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan4_scaled, i, msg->payload); //RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan5_scaled, i, msg->payload); //RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan6_scaled, i, msg->payload); //RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan7_scaled, i, msg->payload); //RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_int16_t_by_index(chan8_scaled, i, msg->payload); //RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
|
||||
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
|
||||
{
|
||||
return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_rc_channels_scaled_pack(mavlink_system.sysid, mavlink_system.compid, &msg, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi);
|
||||
mavlink_msg_rc_channels_scaled_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -38,6 +38,20 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_data_stream_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, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
|
||||
|
||||
i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream.
|
||||
i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream.
|
||||
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type
|
||||
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type
|
||||
i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending.
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
|
||||
{
|
||||
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
|
||||
@ -48,7 +62,7 @@ static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop);
|
||||
mavlink_msg_request_data_stream_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -38,6 +38,20 @@ static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_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 mode, uint8_t axis, uint16_t time)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
|
||||
|
||||
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
|
||||
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
|
||||
i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm
|
||||
i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw
|
||||
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
|
||||
{
|
||||
return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time);
|
||||
@ -48,7 +62,7 @@ static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8
|
||||
static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_request_dynamic_gyro_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, mode, axis, time);
|
||||
mavlink_msg_request_dynamic_gyro_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, mode, axis, time);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t syste
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_static_calibration_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, uint16_t time)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
|
||||
|
||||
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
|
||||
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
|
||||
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration)
|
||||
{
|
||||
return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t sys
|
||||
static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_request_static_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, time);
|
||||
mavlink_msg_request_static_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, time);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint32_t mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude
|
||||
i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude)
|
||||
{
|
||||
return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_
|
||||
static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_altitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode);
|
||||
mavlink_msg_set_altitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
|
||||
i += put_uint8_t_by_index(mode, i, msg->payload); //The new mode
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
|
||||
{
|
||||
return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t co
|
||||
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_mode_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode);
|
||||
mavlink_msg_set_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
|
||||
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //The new navigation mode
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode)
|
||||
{
|
||||
return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_
|
||||
static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_nav_mode_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, nav_mode);
|
||||
mavlink_msg_set_nav_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, nav_mode);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
|
||||
|
||||
i += put_float_by_index(xErr, i, msg->payload); //x position error
|
||||
i += put_float_by_index(yErr, i, msg->payload); //y position error
|
||||
i += put_float_by_index(zErr, i, msg->payload); //z position error
|
||||
i += put_float_by_index(rollErr, i, msg->payload); //roll error (radians)
|
||||
i += put_float_by_index(pitchErr, i, msg->payload); //pitch error (radians)
|
||||
i += put_float_by_index(yawErr, i, msg->payload); //yaw error (radians)
|
||||
i += put_float_by_index(vxErr, i, msg->payload); //x velocity
|
||||
i += put_float_by_index(vyErr, i, msg->payload); //y velocity
|
||||
i += put_float_by_index(vzErr, i, msg->payload); //z velocity
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
|
||||
{
|
||||
return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_state_correction_pack(mavlink_system.sysid, mavlink_system.compid, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr);
|
||||
mavlink_msg_state_correction_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -30,6 +30,17 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t severity, const int8_t* text)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
|
||||
|
||||
i += put_uint8_t_by_index(severity, i, msg->payload); //Severity of status, 0 = info message, 255 = critical fault
|
||||
i += put_array_by_index(text, 50, i, msg->payload); //Status text message, without null termination character
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
|
||||
{
|
||||
return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
|
||||
@ -40,7 +51,7 @@ static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_statustext_pack(mavlink_system.sysid, mavlink_system.compid, &msg, severity, text);
|
||||
mavlink_msg_statustext_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, severity, text);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
|
||||
|
||||
i += put_uint8_t_by_index(mode, i, msg->payload); //System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
|
||||
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //Navigation mode, see MAV_NAV_MODE ENUM
|
||||
i += put_uint8_t_by_index(status, i, msg->payload); //System status flag, see MAV_STATUS ENUM
|
||||
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
|
||||
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage, in millivolts (1 = 1 millivolt)
|
||||
i += put_uint8_t_by_index(motor_block, i, msg->payload); //Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
|
||||
i += put_uint16_t_by_index(packet_drop, i, msg->payload); //Dropped packets (packets that were corrupted on reception on the MAV)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
|
||||
{
|
||||
return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->motor_block, sys_status->packet_drop);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_sys_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, mode, nav_mode, status, load, vbat, motor_block, packet_drop);
|
||||
mavlink_msg_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, status, load, vbat, motor_block, packet_drop);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -26,6 +26,16 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_usec)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
|
||||
|
||||
i += put_uint64_t_by_index(time_usec, i, msg->payload); //Timestamp of the master clock in microseconds since UNIX epoch.
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
|
||||
{
|
||||
return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_usec);
|
||||
@ -36,7 +46,7 @@ static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_system_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, time_usec);
|
||||
mavlink_msg_system_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_usec);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -68,6 +68,30 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_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, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
|
||||
|
||||
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_uint16_t_by_index(seq, i, msg->payload); //Sequence
|
||||
i += put_uint8_t_by_index(frame, i, msg->payload); //The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
|
||||
i += put_uint8_t_by_index(action, i, msg->payload); //The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
|
||||
i += put_float_by_index(orbit, i, msg->payload); //Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
|
||||
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); //Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
|
||||
i += put_float_by_index(param1, i, msg->payload); //For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
|
||||
i += put_float_by_index(param2, i, msg->payload); //For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
|
||||
i += put_uint8_t_by_index(current, i, msg->payload); //false:0, true:1
|
||||
i += put_float_by_index(x, i, msg->payload); //local: x position, global: longitude
|
||||
i += put_float_by_index(y, i, msg->payload); //y position: global: latitude
|
||||
i += put_float_by_index(z, i, msg->payload); //z position: global: altitude
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
|
||||
i += put_uint8_t_by_index(autocontinue, i, msg->payload); //autocontinue to next wp
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
|
||||
{
|
||||
return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->action, waypoint->orbit, waypoint->orbit_direction, waypoint->param1, waypoint->param2, waypoint->current, waypoint->x, waypoint->y, waypoint->z, waypoint->yaw, waypoint->autocontinue);
|
||||
@ -78,7 +102,7 @@ static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t co
|
||||
static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq, frame, action, orbit, orbit_direction, param1, param2, current, x, y, z, yaw, autocontinue);
|
||||
mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, action, orbit, orbit_direction, param1, param2, current, x, y, z, yaw, autocontinue);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_ack_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, uint8_t type)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
|
||||
|
||||
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_uint8_t_by_index(type, i, msg->payload); //0: OK, 1: Error
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack)
|
||||
{
|
||||
return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_
|
||||
static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, type);
|
||||
mavlink_msg_waypoint_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, type);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, ui
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_clear_all_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)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
|
||||
|
||||
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
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all)
|
||||
{
|
||||
return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_clear_all_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component);
|
||||
mavlink_msg_waypoint_clear_all_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_count_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, uint16_t count)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
|
||||
|
||||
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_uint16_t_by_index(count, i, msg->payload); //Number of Waypoints in the Sequence
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count)
|
||||
{
|
||||
return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint
|
||||
static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_count_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, count);
|
||||
mavlink_msg_waypoint_count_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, count);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -26,6 +26,16 @@ static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
|
||||
|
||||
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
|
||||
{
|
||||
return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
|
||||
@ -36,7 +46,7 @@ static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_current_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq);
|
||||
mavlink_msg_waypoint_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -26,6 +26,16 @@ static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
|
||||
|
||||
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached)
|
||||
{
|
||||
return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq);
|
||||
@ -36,7 +46,7 @@ static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_reached_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq);
|
||||
mavlink_msg_waypoint_reached_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_request_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, uint16_t seq)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
|
||||
|
||||
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_uint16_t_by_index(seq, i, msg->payload); //Sequence
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request)
|
||||
{
|
||||
return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_request_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq);
|
||||
mavlink_msg_waypoint_request_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id,
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_request_list_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)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
|
||||
|
||||
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
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list)
|
||||
{
|
||||
return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_i
|
||||
static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_request_list_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component);
|
||||
mavlink_msg_waypoint_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -32,6 +32,18 @@ static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id,
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_set_current_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, uint16_t seq)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
|
||||
|
||||
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_uint16_t_by_index(seq, i, msg->payload); //Sequence
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current)
|
||||
{
|
||||
return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq);
|
||||
@ -42,7 +54,7 @@ static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id
|
||||
static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_set_current_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq);
|
||||
mavlink_msg_waypoint_set_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -53,6 +53,25 @@ static inline uint16_t mavlink_msg_waypoint_set_global_reference_pack(uint8_t sy
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_set_global_reference_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 global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_GLOBAL_REFERENCE;
|
||||
|
||||
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(global_x, i, msg->payload); //global x position
|
||||
i += put_float_by_index(global_y, i, msg->payload); //global y position
|
||||
i += put_float_by_index(global_z, i, msg->payload); //global z position
|
||||
i += put_float_by_index(global_yaw, i, msg->payload); //global yaw orientation in radians, 0 = NORTH
|
||||
i += put_float_by_index(local_x, i, msg->payload); //local x position that matches the global x position
|
||||
i += put_float_by_index(local_y, i, msg->payload); //local y position that matches the global y position
|
||||
i += put_float_by_index(local_z, i, msg->payload); //local z position that matches the global z position
|
||||
i += put_float_by_index(local_yaw, i, msg->payload); //local yaw that matches the global yaw orientation
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_waypoint_set_global_reference_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_global_reference_t* waypoint_set_global_reference)
|
||||
{
|
||||
return mavlink_msg_waypoint_set_global_reference_pack(system_id, component_id, msg, waypoint_set_global_reference->target_system, waypoint_set_global_reference->target_component, waypoint_set_global_reference->global_x, waypoint_set_global_reference->global_y, waypoint_set_global_reference->global_z, waypoint_set_global_reference->global_yaw, waypoint_set_global_reference->local_x, waypoint_set_global_reference->local_y, waypoint_set_global_reference->local_z, waypoint_set_global_reference->local_yaw);
|
||||
@ -63,7 +82,7 @@ static inline uint16_t mavlink_msg_waypoint_set_global_reference_encode(uint8_t
|
||||
static inline void mavlink_msg_waypoint_set_global_reference_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_waypoint_set_global_reference_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, global_x, global_y, global_z, global_yaw, local_x, local_y, local_z, local_yaw);
|
||||
mavlink_msg_waypoint_set_global_reference_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, global_x, global_y, global_z, global_yaw, local_x, local_y, local_z, local_yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -189,7 +189,8 @@ typedef struct __mavlink_status {
|
||||
uint8_t parse_error; ///< Number of parse errors
|
||||
mavlink_parse_state_t parse_state; ///< Parsing state machine
|
||||
uint8_t packet_idx; ///< Index in current packet
|
||||
uint8_t current_seq; ///< Sequence number of last packet
|
||||
uint8_t current_rx_seq; ///< Sequence number of last packet received
|
||||
uint8_t current_tx_seq; ///< Sequence number of last packet sent
|
||||
uint16_t packet_rx_success_count; ///< Received packets
|
||||
uint16_t packet_rx_drop_count; ///< Number of packet drops
|
||||
} mavlink_status_t;
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, October 24 2010, 08:46 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:43 UTC
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
@ -50,6 +50,24 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
|
||||
i += put_float_by_index(roll, i, msg->payload); //roll
|
||||
i += put_float_by_index(pitch, i, msg->payload); //pitch
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw
|
||||
i += put_float_by_index(thrust, i, msg->payload); //thrust
|
||||
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
|
||||
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
|
||||
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
|
||||
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control)
|
||||
{
|
||||
return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
|
||||
@ -60,7 +78,7 @@ static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_attitude_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
|
||||
mavlink_msg_attitude_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_aux_status_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_aux_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
|
||||
|
||||
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
|
||||
i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); //Number of I2C errors since startup
|
||||
i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); //Number of I2C errors since startup
|
||||
i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); //Number of I2C errors since startup
|
||||
i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); //Number of I2C errors since startup
|
||||
i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); //Number of I2C errors since startup
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status)
|
||||
{
|
||||
return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_aux_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count);
|
||||
mavlink_msg_aux_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
|
||||
|
||||
i += put_uint8_t_by_index(position_fix, i, msg->payload); //Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
|
||||
i += put_uint8_t_by_index(vision_fix, i, msg->payload); //Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
|
||||
i += put_uint8_t_by_index(gps_fix, i, msg->payload); //GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
|
||||
i += put_uint8_t_by_index(control_att, i, msg->payload); //0: Attitude control disabled, 1: enabled
|
||||
i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); //0: X, Y position control disabled, 1: enabled
|
||||
i += put_uint8_t_by_index(control_pos_z, i, msg->payload); //0: Z position control disabled, 1: enabled
|
||||
i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); //0: Yaw angle control disabled, 1: enabled
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status)
|
||||
{
|
||||
return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint
|
||||
static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_control_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, position_fix, vision_fix, gps_fix, control_att, control_pos_xy, control_pos_z, control_pos_yaw);
|
||||
mavlink_msg_control_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, position_fix, vision_fix, gps_fix, control_att, control_pos_xy, control_pos_z, control_pos_yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -39,6 +39,20 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
|
||||
|
||||
i += put_array_by_index(name, 10, i, msg->payload); //Name
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
|
||||
i += put_float_by_index(x, i, msg->payload); //x
|
||||
i += put_float_by_index(y, i, msg->payload); //y
|
||||
i += put_float_by_index(z, i, msg->payload); //z
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
|
||||
{
|
||||
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
|
||||
@ -49,7 +63,7 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const int8_t* name, uint64_t usec, float x, float y, float z)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_debug_vect_pack(mavlink_system.sysid, mavlink_system.compid, &msg, name, usec, x, y, z);
|
||||
mavlink_msg_debug_vect_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, usec, x, y, z);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -68,6 +68,30 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
|
||||
|
||||
i += put_uint64_t_by_index(cam_id, i, msg->payload); //Camera id
|
||||
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera # (starts with 0)
|
||||
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
|
||||
i += put_uint64_t_by_index(valid_until, i, msg->payload); //Until which timestamp this buffer will stay valid
|
||||
i += put_uint32_t_by_index(img_seq, i, msg->payload); //The image sequence number
|
||||
i += put_uint32_t_by_index(img_buf_index, i, msg->payload); //Position of the image in the buffer, starts with 0
|
||||
i += put_uint16_t_by_index(width, i, msg->payload); //Image width
|
||||
i += put_uint16_t_by_index(height, i, msg->payload); //Image height
|
||||
i += put_uint16_t_by_index(depth, i, msg->payload); //Image depth
|
||||
i += put_uint8_t_by_index(channels, i, msg->payload); //Image channels
|
||||
i += put_uint32_t_by_index(key, i, msg->payload); //Shared memory area key
|
||||
i += put_uint32_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
|
||||
i += put_float_by_index(gain, i, msg->payload); //Camera gain
|
||||
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
|
||||
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available)
|
||||
{
|
||||
return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch);
|
||||
@ -78,7 +102,7 @@ static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_image_available_pack(mavlink_system.sysid, mavlink_system.compid, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch);
|
||||
mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -26,6 +26,16 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id,
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enable)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
|
||||
|
||||
i += put_uint8_t_by_index(enable, i, msg->payload); //0 to disable, 1 to enable
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control)
|
||||
{
|
||||
return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable);
|
||||
@ -36,7 +46,7 @@ static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_i
|
||||
static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_image_trigger_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enable);
|
||||
mavlink_msg_image_trigger_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enable);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
|
||||
|
||||
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
|
||||
i += put_uint32_t_by_index(seq, i, msg->payload); //IMU seq
|
||||
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
|
||||
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
|
||||
{
|
||||
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_image_triggered_pack(mavlink_system.sysid, mavlink_system.compid, &msg, timestamp, seq, roll, pitch);
|
||||
mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_MARKER;
|
||||
|
||||
i += put_uint16_t_by_index(id, i, msg->payload); //ID
|
||||
i += put_float_by_index(x, i, msg->payload); //x position
|
||||
i += put_float_by_index(y, i, msg->payload); //y position
|
||||
i += put_float_by_index(z, i, msg->payload); //z position
|
||||
i += put_float_by_index(roll, i, msg->payload); //roll orientation
|
||||
i += put_float_by_index(pitch, i, msg->payload); //pitch orientation
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
|
||||
{
|
||||
return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t comp
|
||||
static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_marker_pack(mavlink_system.sysid, mavlink_system.compid, &msg, id, x, y, z, roll, pitch, yaw);
|
||||
mavlink_msg_marker_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, roll, pitch, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -36,6 +36,19 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
|
||||
|
||||
i += put_uint8_t_by_index(type, i, msg->payload); //0: Pattern, 1: Letter
|
||||
i += put_float_by_index(confidence, i, msg->payload); //Confidence of detection
|
||||
i += put_array_by_index(file, 100, i, msg->payload); //Pattern file name
|
||||
i += put_uint8_t_by_index(detected, i, msg->payload); //Accepted as true detection, 0 no, 1 yes
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected)
|
||||
{
|
||||
return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
|
||||
@ -46,7 +59,7 @@ static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_pattern_detected_pack(mavlink_system.sysid, mavlink_system.compid, &msg, type, confidence, file, detected);
|
||||
mavlink_msg_pattern_detected_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, confidence, file, detected);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t syst
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_offset_set_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 x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
|
||||
|
||||
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(x, i, msg->payload); //x position offset
|
||||
i += put_float_by_index(y, i, msg->payload); //y position offset
|
||||
i += put_float_by_index(z, i, msg->payload); //z position offset
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation offset in radians, 0 = NORTH
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set)
|
||||
{
|
||||
return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t sy
|
||||
static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_position_control_offset_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, x, y, z, yaw);
|
||||
mavlink_msg_position_control_offset_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -38,6 +38,20 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
|
||||
|
||||
i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
|
||||
i += put_float_by_index(x, i, msg->payload); //x position
|
||||
i += put_float_by_index(y, i, msg->payload); //y position
|
||||
i += put_float_by_index(z, i, msg->payload); //z position
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint)
|
||||
{
|
||||
return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
|
||||
@ -48,7 +62,7 @@ static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t syst
|
||||
static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_position_control_setpoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, id, x, y, z, yaw);
|
||||
mavlink_msg_position_control_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t sy
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_setpoint_set_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, uint16_t id, float x, float y, float z, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
|
||||
|
||||
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_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
|
||||
i += put_float_by_index(x, i, msg->payload); //x position
|
||||
i += put_float_by_index(y, i, msg->payload); //y position
|
||||
i += put_float_by_index(z, i, msg->payload); //z position
|
||||
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
|
||||
{
|
||||
return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t
|
||||
static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_position_control_setpoint_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, id, x, y, z, yaw);
|
||||
mavlink_msg_position_control_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, id, x, y, z, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
|
||||
|
||||
i += put_uint16_t_by_index(adc1, i, msg->payload); //ADC1 (J405 ADC3, LPC2148 AD0.6)
|
||||
i += put_uint16_t_by_index(adc2, i, msg->payload); //ADC2 (J405 ADC5, LPC2148 AD0.2)
|
||||
i += put_uint16_t_by_index(adc3, i, msg->payload); //ADC3 (J405 ADC6, LPC2148 AD0.1)
|
||||
i += put_uint16_t_by_index(adc4, i, msg->payload); //ADC4 (J405 ADC7, LPC2148 AD1.3)
|
||||
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage
|
||||
i += put_int16_t_by_index(temp, i, msg->payload); //Temperature (degrees celcius)
|
||||
i += put_int32_t_by_index(baro, i, msg->payload); //Barometric pressure (hecto Pascal)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
|
||||
{
|
||||
return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t com
|
||||
static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_raw_aux_pack(mavlink_system.sysid, mavlink_system.compid, &msg, adc1, adc2, adc3, adc4, vbat, temp, baro);
|
||||
mavlink_msg_raw_aux_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, adc1, adc2, adc3, adc4, vbat, temp, baro);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
|
||||
|
||||
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera id
|
||||
i += put_uint8_t_by_index(cam_mode, i, msg->payload); //Camera mode: 0 = auto, 1 = manual
|
||||
i += put_uint8_t_by_index(trigger_pin, i, msg->payload); //Trigger pin, 0-3 for PtGrey FireFly
|
||||
i += put_uint16_t_by_index(interval, i, msg->payload); //Shutter interval, in microseconds
|
||||
i += put_uint16_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
|
||||
i += put_float_by_index(gain, i, msg->payload); //Camera gain
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
|
||||
{
|
||||
return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uin
|
||||
static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_set_cam_shutter_pack(mavlink_system.sysid, mavlink_system.compid, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain);
|
||||
mavlink_msg_set_cam_shutter_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
|
||||
i += put_float_by_index(x, i, msg->payload); //Global X position
|
||||
i += put_float_by_index(y, i, msg->payload); //Global Y position
|
||||
i += put_float_by_index(z, i, msg->payload); //Global Z position
|
||||
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
|
||||
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
|
||||
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
|
||||
{
|
||||
return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system
|
||||
static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_vicon_position_estimate_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, roll, pitch, yaw);
|
||||
mavlink_msg_vicon_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
|
||||
|
||||
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
|
||||
i += put_float_by_index(x, i, msg->payload); //Global X position
|
||||
i += put_float_by_index(y, i, msg->payload); //Global Y position
|
||||
i += put_float_by_index(z, i, msg->payload); //Global Z position
|
||||
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
|
||||
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
|
||||
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
|
||||
{
|
||||
return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t syste
|
||||
static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_vision_position_estimate_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, roll, pitch, yaw);
|
||||
mavlink_msg_vision_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
|
||||
|
||||
i += put_uint8_t_by_index(target_system_id, i, msg->payload); //Target system ID
|
||||
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
|
||||
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
|
||||
i += put_uint8_t_by_index(command_id, i, msg->payload); //Command ID
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
|
||||
{
|
||||
return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, ui
|
||||
static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_watchdog_command_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system_id, watchdog_id, process_id, command_id);
|
||||
mavlink_msg_watchdog_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system_id, watchdog_id, process_id, command_id);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -29,6 +29,17 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, ui
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
|
||||
|
||||
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
|
||||
i += put_uint16_t_by_index(process_count, i, msg->payload); //Number of processes
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
|
||||
{
|
||||
return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
|
||||
@ -39,7 +50,7 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id,
|
||||
static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_watchdog_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_count);
|
||||
mavlink_msg_watchdog_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_count);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -40,6 +40,20 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id,
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
|
||||
|
||||
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
|
||||
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
|
||||
i += put_array_by_index(name, 100, i, msg->payload); //Process name
|
||||
i += put_array_by_index(arguments, 147, i, msg->payload); //Process arguments
|
||||
i += put_int32_t_by_index(timeout, i, msg->payload); //Timeout (seconds)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
|
||||
{
|
||||
return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
|
||||
@ -50,7 +64,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_i
|
||||
static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_watchdog_process_info_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_id, name, arguments, timeout);
|
||||
mavlink_msg_watchdog_process_info_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, name, arguments, timeout);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
|
||||
|
||||
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
|
||||
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
|
||||
i += put_uint8_t_by_index(state, i, msg->payload); //Is running / finished / suspended / crashed
|
||||
i += put_uint8_t_by_index(muted, i, msg->payload); //Is muted
|
||||
i += put_int32_t_by_index(pid, i, msg->payload); //PID
|
||||
i += put_uint16_t_by_index(crashes, i, msg->payload); //Number of crashes
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
|
||||
{
|
||||
return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system
|
||||
static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_watchdog_process_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_id, state, muted, pid, crashes);
|
||||
mavlink_msg_watchdog_process_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, state, muted, pid, crashes);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, October 24 2010, 08:46 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:43 UTC
|
||||
*/
|
||||
#ifndef PIXHAWK_H
|
||||
#define PIXHAWK_H
|
||||
@ -17,11 +17,19 @@ extern "C" {
|
||||
|
||||
|
||||
#include "../common/common.h"
|
||||
#include "./mavlink_msg_set_altitude.h"
|
||||
#include "./mavlink_msg_request_data_stream.h"
|
||||
#include "./mavlink_msg_request_dynamic_gyro_calibration.h"
|
||||
#include "./mavlink_msg_request_static_calibration.h"
|
||||
#include "./mavlink_msg_manual_control.h"
|
||||
// ENUM DEFINITIONS
|
||||
|
||||
/** @brief Slugs parameter interface subsets */
|
||||
enum SLUGS_PID_INDX_IDS
|
||||
{
|
||||
PID_YAW_DAMPER=2,
|
||||
PID_PITCH=3, /* With comment: PID Pitch parameter*/
|
||||
PID_ALT_HOLD=50
|
||||
};
|
||||
|
||||
|
||||
// MESSAGE DEFINITIONS
|
||||
|
||||
#include "./mavlink_msg_attitude_control.h"
|
||||
#include "./mavlink_msg_debug_vect.h"
|
||||
#include "./mavlink_msg_set_cam_shutter.h"
|
||||
@ -42,6 +50,8 @@ extern "C" {
|
||||
#include "./mavlink_msg_watchdog_process_status.h"
|
||||
#include "./mavlink_msg_watchdog_command.h"
|
||||
#include "./mavlink_msg_pattern_detected.h"
|
||||
#include "./mavlink_msg_point_of_interest.h"
|
||||
#include "./mavlink_msg_point_of_interest_connection.h"
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
@ -6,12 +6,60 @@
|
||||
|
||||
#include "mavlink_types.h"
|
||||
|
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message
|
||||
* @brief Initialize the communication stack
|
||||
*
|
||||
* This function has to be called before using commParseBuffer() to initialize the different status registers.
|
||||
*
|
||||
* @return Will initialize the different buffers and status registers.
|
||||
*/
|
||||
static void mavlink_parse_state_initialize(mavlink_status_t* initStatus)
|
||||
{
|
||||
if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1))
|
||||
{
|
||||
initStatus->ck_a = 0;
|
||||
initStatus->ck_b = 0;
|
||||
initStatus->msg_received = 0;
|
||||
initStatus->buffer_overrun = 0;
|
||||
initStatus->parse_error = 0;
|
||||
initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT;
|
||||
initStatus->packet_idx = 0;
|
||||
initStatus->packet_rx_drop_count = 0;
|
||||
initStatus->packet_rx_success_count = 0;
|
||||
initStatus->current_rx_seq = 0;
|
||||
initStatus->current_tx_seq = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
|
||||
{
|
||||
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH];
|
||||
#else
|
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB];
|
||||
#endif
|
||||
|
||||
return &m_mavlink_status[chan];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
|
||||
*
|
||||
* This function calculates the checksum and sets length and aircraft id correctly.
|
||||
* It assumes that the message id and the payload are already correctly set.
|
||||
*
|
||||
* @warning This function implicitely assumes the message is sent over channel zero.
|
||||
* if the message is sent over a different channel it will reach the receiver
|
||||
* without error, BUT the sequence number might be wrong due to the wrong
|
||||
* channel sequence counter. This will result is wrongly reported excessive
|
||||
* packet loss. Please use @see mavlink_{pack|encode}_headerless and then
|
||||
* @see mavlink_finalize_message_chan before sending for a correct channel
|
||||
* assignment. Please note that the mavlink_msg_xxx_pack and encode functions
|
||||
* assign channel zero as default and thus induce possible loss counter errors.\
|
||||
* They have been left to ensure code compatibility.
|
||||
*
|
||||
* @see mavlink_finalize_message_chan
|
||||
* @param msg Message to finalize
|
||||
* @param system_id Id of the sending (this) system, 1-127
|
||||
* @param length Message length, usually just the counter incremented while packing the message
|
||||
@ -19,14 +67,42 @@
|
||||
static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length)
|
||||
{
|
||||
// This code part is the same for all messages;
|
||||
static uint8_t seq = 0;
|
||||
uint16_t checksum;
|
||||
msg->len = length;
|
||||
msg->sysid = system_id;
|
||||
msg->compid = component_id;
|
||||
// One sequence number per component
|
||||
msg->seq = seq++;
|
||||
msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq;
|
||||
mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1;
|
||||
checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
|
||||
msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
|
||||
msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
|
||||
|
||||
return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Finalize a MAVLink message with channel assignment
|
||||
*
|
||||
* This function calculates the checksum and sets length and aircraft id correctly.
|
||||
* It assumes that the message id and the payload are already correctly set. This function
|
||||
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
|
||||
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
|
||||
*
|
||||
* @param msg Message to finalize
|
||||
* @param system_id Id of the sending (this) system, 1-127
|
||||
* @param length Message length, usually just the counter incremented while packing the message
|
||||
*/
|
||||
static inline uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint16_t length)
|
||||
{
|
||||
// This code part is the same for all messages;
|
||||
uint16_t checksum;
|
||||
msg->len = length;
|
||||
msg->sysid = system_id;
|
||||
msg->compid = component_id;
|
||||
// One sequence number per component
|
||||
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
|
||||
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
|
||||
checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
|
||||
msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
|
||||
msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
|
||||
@ -88,30 +164,6 @@ static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
|
||||
msg->ck_b = ck.c[1];
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initialize the communication stack
|
||||
*
|
||||
* This function has to be called before using commParseBuffer() to initialize the different status registers.
|
||||
*
|
||||
* @return Will initialize the different buffers and status registers.
|
||||
*/
|
||||
static void mavlink_parse_state_initialize(mavlink_status_t* initStatus)
|
||||
{
|
||||
if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1))
|
||||
{
|
||||
initStatus->ck_a = 0;
|
||||
initStatus->ck_b = 0;
|
||||
initStatus->msg_received = 0;
|
||||
initStatus->buffer_overrun = 0;
|
||||
initStatus->parse_error = 0;
|
||||
initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT;
|
||||
initStatus->packet_idx = 0;
|
||||
initStatus->packet_rx_drop_count = 0;
|
||||
initStatus->packet_rx_success_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This is a convenience function which handles the complete MAVLink parsing.
|
||||
* the function will parse one byte at a time and return the complete packet once
|
||||
@ -151,17 +203,15 @@ static void mavlink_parse_state_initialize(mavlink_status_t* initStatus)
|
||||
static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
|
||||
{
|
||||
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH];
|
||||
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH];
|
||||
#else
|
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB];
|
||||
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB];
|
||||
#endif
|
||||
// Initializes only once, values keep unchanged after first initialization
|
||||
mavlink_parse_state_initialize(&m_mavlink_status[chan]);
|
||||
mavlink_parse_state_initialize(mavlink_get_channel_status(chan));
|
||||
|
||||
mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
|
||||
mavlink_status_t* status = &m_mavlink_status[chan]; ///< The current decode status
|
||||
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
|
||||
int bufferIndex = 0;
|
||||
|
||||
status->msg_received = 0;
|
||||
@ -285,16 +335,17 @@ static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messag
|
||||
// status->packet_rx_drop_count++;
|
||||
// status->current_seq++;
|
||||
//}
|
||||
status->current_seq = rxmsg->seq;
|
||||
status->current_rx_seq = rxmsg->seq;
|
||||
// Initial condition: If no packet has been received so far, drop count is undefined
|
||||
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
|
||||
// Count this packet as received
|
||||
status->packet_rx_success_count++;
|
||||
}
|
||||
|
||||
r_mavlink_status->current_seq = status->current_seq+1;
|
||||
r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
|
||||
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
|
||||
r_mavlink_status->packet_rx_drop_count = status->parse_error;
|
||||
status->parse_error = 0;
|
||||
return status->msg_received;
|
||||
}
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, October 24 2010, 08:47 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t comp
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the air data
|
||||
i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa)
|
||||
i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa)
|
||||
i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
|
||||
{
|
||||
return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->target, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t co
|
||||
static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_air_data_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dynamicPressure, staticPressure, temperature);
|
||||
mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dynamicPressure, staticPressure, temperature);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,19 @@ static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t comp
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the CPU load
|
||||
i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load
|
||||
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load
|
||||
i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load)
|
||||
{
|
||||
return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->target, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt);
|
||||
@ -45,7 +58,7 @@ static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t co
|
||||
static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_cpu_load_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, sensLoad, ctrlLoad, batVolt);
|
||||
mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, sensLoad, ctrlLoad, batVolt);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t co
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
|
||||
i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1
|
||||
i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2
|
||||
i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3
|
||||
i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1
|
||||
i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2
|
||||
i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic)
|
||||
{
|
||||
return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->target, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_diagnostic_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
|
||||
mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -41,6 +41,21 @@ static inline uint16_t mavlink_msg_pilot_console_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pilot_console_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PILOT_CONSOLE;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
|
||||
i += put_uint16_t_by_index(dt, i, msg->payload); //Pilot's console throttle command
|
||||
i += put_uint16_t_by_index(dla, i, msg->payload); //Pilot's console left aileron command
|
||||
i += put_uint16_t_by_index(dra, i, msg->payload); //Pilot's console right aileron command
|
||||
i += put_uint16_t_by_index(dr, i, msg->payload); //Pilot's console rudder command
|
||||
i += put_uint16_t_by_index(de, i, msg->payload); //Pilot's console elevator command
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pilot_console_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pilot_console_t* pilot_console)
|
||||
{
|
||||
return mavlink_msg_pilot_console_pack(system_id, component_id, msg, pilot_console->target, pilot_console->dt, pilot_console->dla, pilot_console->dra, pilot_console->dr, pilot_console->de);
|
||||
@ -51,7 +66,7 @@ static inline uint16_t mavlink_msg_pilot_console_encode(uint8_t system_id, uint8
|
||||
static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_pilot_console_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dt, dla, dra, dr, de);
|
||||
mavlink_msg_pilot_console_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dt, dla, dra, dr, de);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -56,6 +56,26 @@ static inline uint16_t mavlink_msg_pwm_commands_pack(uint8_t system_id, uint8_t
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pwm_commands_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_PWM_COMMANDS;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
|
||||
i += put_uint16_t_by_index(dt_c, i, msg->payload); //AutoPilot's throttle command
|
||||
i += put_uint16_t_by_index(dla_c, i, msg->payload); //AutoPilot's left aileron command
|
||||
i += put_uint16_t_by_index(dra_c, i, msg->payload); //AutoPilot's right aileron command
|
||||
i += put_uint16_t_by_index(dr_c, i, msg->payload); //AutoPilot's rudder command
|
||||
i += put_uint16_t_by_index(dle_c, i, msg->payload); //AutoPilot's left elevator command
|
||||
i += put_uint16_t_by_index(dre_c, i, msg->payload); //AutoPilot's right elevator command
|
||||
i += put_uint16_t_by_index(dlf_c, i, msg->payload); //AutoPilot's left flap command
|
||||
i += put_uint16_t_by_index(drf_c, i, msg->payload); //AutoPilot's right flap command
|
||||
i += put_uint16_t_by_index(aux1, i, msg->payload); //AutoPilot's aux1 command
|
||||
i += put_uint16_t_by_index(aux2, i, msg->payload); //AutoPilot's aux2 command
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_pwm_commands_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pwm_commands_t* pwm_commands)
|
||||
{
|
||||
return mavlink_msg_pwm_commands_pack(system_id, component_id, msg, pwm_commands->target, pwm_commands->dt_c, pwm_commands->dla_c, pwm_commands->dra_c, pwm_commands->dr_c, pwm_commands->dle_c, pwm_commands->dre_c, pwm_commands->dlf_c, pwm_commands->drf_c, pwm_commands->aux1, pwm_commands->aux2);
|
||||
@ -66,7 +86,7 @@ static inline uint16_t mavlink_msg_pwm_commands_encode(uint8_t system_id, uint8_
|
||||
static inline void mavlink_msg_pwm_commands_send(mavlink_channel_t chan, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_pwm_commands_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dt_c, dla_c, dra_c, dr_c, dle_c, dre_c, dlf_c, drf_c, aux1, aux2);
|
||||
mavlink_msg_pwm_commands_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dt_c, dla_c, dra_c, dr_c, dle_c, dre_c, dlf_c, drf_c, aux1, aux2);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -44,6 +44,22 @@ static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t c
|
||||
return mavlink_finalize_message(msg, system_id, component_id, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
|
||||
|
||||
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the biases
|
||||
i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s)
|
||||
i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s)
|
||||
i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s)
|
||||
i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s)
|
||||
i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s)
|
||||
i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s)
|
||||
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
|
||||
}
|
||||
|
||||
static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
|
||||
{
|
||||
return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->target, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
|
||||
@ -54,7 +70,7 @@ static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t
|
||||
static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_sensor_bias_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
|
||||
mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
|
||||
mavlink_send_uart(chan, &msg);
|
||||
}
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol.
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
* Generated on Sunday, October 24 2010, 08:47 UTC
|
||||
* Generated on Thursday, December 2 2010, 10:44 UTC
|
||||
*/
|
||||
#ifndef SLUGS_H
|
||||
#define SLUGS_H
|
||||
@ -17,6 +17,11 @@ extern "C" {
|
||||
|
||||
|
||||
#include "../common/common.h"
|
||||
// ENUM DEFINITIONS
|
||||
|
||||
|
||||
// MESSAGE DEFINITIONS
|
||||
|
||||
#include "./mavlink_msg_cpu_load.h"
|
||||
#include "./mavlink_msg_air_data.h"
|
||||
#include "./mavlink_msg_sensor_bias.h"
|
||||
|
@ -1,46 +1,17 @@
|
||||
<?xml version="1.0"?>
|
||||
<mavlink>
|
||||
<include>common.xml</include>
|
||||
|
||||
<enums>
|
||||
<enum name="SLUGS_PID_INDX_IDS" >
|
||||
<description>Slugs parameter interface subsets</description>
|
||||
<entry name = "PID_YAW_DAMPER" value="2" />
|
||||
<entry name = "PID_PITCH">With comment: PID Pitch parameter</entry>
|
||||
<entry name = "PID_ALT_HOLD" value="50" />
|
||||
</enum>
|
||||
</enums>
|
||||
|
||||
<messages>
|
||||
<message name="SET_ALTITUDE" id="80">
|
||||
<field name="target" type="uint8_t">The system setting the altitude</field>
|
||||
<field name="mode" type="uint32_t">The new altitude in meters</field>
|
||||
</message>
|
||||
|
||||
<message name="REQUEST_DATA_STREAM" id="81">
|
||||
<field name="target_system" type="uint8_t">The target requested to send the message stream.</field>
|
||||
<field name="target_component" type="uint8_t">The target requested to send the message stream.</field>
|
||||
<field name="req_stream_id" type="uint8_t">The ID of the requested message type</field>
|
||||
<field name="req_message_rate" type="uint16_t">The requested interval between two messages of this type</field>
|
||||
<field name="start_stop" type="uint8_t">1 to start sending, 0 to stop sending.</field>
|
||||
</message>
|
||||
|
||||
<message name="REQUEST_DYNAMIC_GYRO_CALIBRATION" id="82">
|
||||
<field name="target_system" type="uint8_t">The system which should auto-calibrate</field>
|
||||
<field name="target_component" type="uint8_t">The system component which should auto-calibrate</field>
|
||||
<field name="mode" type="float">The current ground-truth rpm</field>
|
||||
<field name="axis" type="uint8_t">The axis to calibrate: 0 roll, 1 pitch, 2 yaw</field>
|
||||
<field name="time" type="uint16_t">The time to average over in ms</field>
|
||||
</message>
|
||||
|
||||
<message name="REQUEST_STATIC_CALIBRATION" id="83">
|
||||
<field name="target_system" type="uint8_t">The system which should auto-calibrate</field>
|
||||
<field name="target_component" type="uint8_t">The system component which should auto-calibrate</field>
|
||||
<field name="time" type="uint16_t">The time to average over in ms</field>
|
||||
</message>
|
||||
|
||||
<message name="MANUAL_CONTROL" id="84">
|
||||
<field name="target" type="uint8_t">The system to be controlled</field>
|
||||
<field name="roll" type="float">roll</field>
|
||||
<field name="pitch" type="float">pitch</field>
|
||||
<field name="yaw" type="float">yaw</field>
|
||||
<field name="thrust" type="float">thrust</field>
|
||||
<field name="roll_manual" type="uint8_t">roll control enabled auto:0, manual:1</field>
|
||||
<field name="pitch_manual" type="uint8_t">pitch auto:0, manual:1</field>
|
||||
<field name="yaw_manual" type="uint8_t">yaw auto:0, manual:1</field>
|
||||
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
|
||||
</message>
|
||||
|
||||
<message name="ATTITUDE_CONTROL" id="85">
|
||||
<field name="target" type="uint8_t">The system to be controlled</field>
|
||||
<field name="roll" type="float">roll</field>
|
||||
@ -224,5 +195,36 @@
|
||||
<field name="detected" type="uint8_t">Accepted as true detection, 0 no, 1 yes</field>
|
||||
</message>
|
||||
|
||||
<message name="POINT_OF_INTEREST" id="161">
|
||||
<description>Notifies the operator about a point of interest (POI). This can be anything detected by the
|
||||
system. This generic message is intented to help interfacing to generic visualizations and to display
|
||||
the POI on a map.</description>
|
||||
<field name="type" type="uint8_t">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
||||
<field name="color" type="uint8_t">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
||||
<field name="coordinate_system" type="uint8_t">0: global, 1:local</field>
|
||||
<field name="timeout" type="uint16_t">0: no timeout, >1: timeout in seconds</field>
|
||||
<field name="x" type="float">X Position</field>
|
||||
<field name="y" type="float">Y Position</field>
|
||||
<field name="z" type="float">Z Position</field>
|
||||
<field name="name" type="array[25]">POI name</field>
|
||||
</message>
|
||||
|
||||
<message name="POINT_OF_INTEREST_CONNECTION" id="162">
|
||||
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
|
||||
system. This generic message is intented to help interfacing to generic visualizations and to display
|
||||
the POI on a map.</description>
|
||||
<field name="type" type="uint8_t">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
|
||||
<field name="color" type="uint8_t">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
|
||||
<field name="coordinate_system" type="uint8_t">0: global, 1:local</field>
|
||||
<field name="timeout" type="uint16_t">0: no timeout, >1: timeout in seconds</field>
|
||||
<field name="xp1" type="float">X1 Position</field>
|
||||
<field name="yp1" type="float">Y1 Position</field>
|
||||
<field name="zp1" type="float">Z1 Position</field>
|
||||
<field name="xp2" type="float">X2 Position</field>
|
||||
<field name="yp2" type="float">Y2 Position</field>
|
||||
<field name="zp2" type="float">Z2 Position</field>
|
||||
<field name="name" type="array[25]">POI connection name</field>
|
||||
</message>
|
||||
|
||||
</messages>
|
||||
</mavlink>
|
||||
|
6
libraries/GCS_MAVLink/sync
Executable file
6
libraries/GCS_MAVLink/sync
Executable file
@ -0,0 +1,6 @@
|
||||
#!/bin/sh
|
||||
rm -rf _tmp
|
||||
git clone git://github.com/pixhawk/mavlink.git -b dev _tmp
|
||||
rm -rf _tmp/.git
|
||||
rsync -av _tmp/* .
|
||||
rm -rf _tmp
|
Loading…
Reference in New Issue
Block a user