This commit is contained in:
Craig Elder 2014-09-11 23:06:10 -07:00
commit f9f6f39d61
26 changed files with 564 additions and 275 deletions

View File

@ -808,7 +808,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: THR_ACCEL_IMAX
// @DisplayName: Throttle acceleration controller I gain maximum
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
// @Range: 0 500
// @Range: 0 1000
// @Units: Percent*10
// @User: Standard

View File

@ -1,5 +1,21 @@
ArduCopter Release Notes:
------------------------------------------------------------------
ArduCopter 3.2-rc9 11-Sep-2014
Changes from 3.2-rc8
1) FRAM bug fix that could stop Mission or Parameter changes from being saved (Pixhawk, VRBrain only)
------------------------------------------------------------------
ArduCopter 3.2-rc8 11-Sep-2014
Changes from 3.2-rc7
1) EKF reduced ripple to resolve copter motor pulsing
2) Default Param changes:
a) AltHold Rate P reduced from 6 to 5
b) AltHold Accel P reduced from 0.75 to 0.5, I from 1.5 to 1.0
c) EKF check threshold increased from 0.6 to 0.8 to reduce false positives
3) sensor health flags sent to GCS only after initialisation to remove false alerts
4) suppress bad terrain data alerts
5) Bug Fix:
a)PX4 dataflash RAM useage reduced to 8k so it works again
------------------------------------------------------------------
ArduCopter 3.2-rc7 04-Sep-2014
Changes from 3.2-rc6
1) Safety Items:

View File

@ -416,22 +416,22 @@
// FLIGHT_MODE
//
#if !defined(FLIGHT_MODE_1)
#ifndef FLIGHT_MODE_1
# define FLIGHT_MODE_1 STABILIZE
#endif
#if !defined(FLIGHT_MODE_2)
#ifndef FLIGHT_MODE_2
# define FLIGHT_MODE_2 STABILIZE
#endif
#if !defined(FLIGHT_MODE_3)
#ifndef FLIGHT_MODE_3
# define FLIGHT_MODE_3 STABILIZE
#endif
#if !defined(FLIGHT_MODE_4)
#ifndef FLIGHT_MODE_4
# define FLIGHT_MODE_4 STABILIZE
#endif
#if !defined(FLIGHT_MODE_5)
#ifndef FLIGHT_MODE_5
# define FLIGHT_MODE_5 STABILIZE
#endif
#if !defined(FLIGHT_MODE_6)
#ifndef FLIGHT_MODE_6
# define FLIGHT_MODE_6 STABILIZE
#endif

View File

@ -325,12 +325,27 @@ static void rtl_land_run()
int16_t roll_control = 0, pitch_control = 0;
float target_yaw_rate = 0;
// if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed || !inertial_nav.position_ok()) {
if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// set target to current position
wp_nav.init_loiter_target();
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
// disarm when the landing detector says we've landed and throttle is at minimum
if (ap.land_complete && (g.rc_3.control_in == 0 || failsafe.radio)) {
init_disarm_motors();
}
#else
// disarm when the landing detector says we've landed
if (ap.land_complete) {
init_disarm_motors();
}
#endif
// check if we've completed this stage of RTL
rtl_state_complete = ap.land_complete;
return;
}
@ -365,18 +380,6 @@ static void rtl_land_run()
// check if we've completed this stage of RTL
rtl_state_complete = ap.land_complete;
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
// disarm when the landing detector says we've landed and throttle is at minimum
if (ap.land_complete && (g.rc_3.control_in == 0 || failsafe.radio)) {
init_disarm_motors();
}
#else
// disarm when the landing detector says we've landed
if (ap.land_complete) {
init_disarm_motors();
}
#endif
}
// get_RTL_alt - return altitude which vehicle should return home at

View File

@ -182,16 +182,6 @@ static void init_arm_motors()
// set hover throttle
motors.set_mid_throttle(g.throttle_mid);
// Cancel arming if throttle is raised too high so that copter does not suddenly take off
read_radio();
if (g.rc_3.control_in > g.throttle_cruise && g.throttle_cruise > 100) {
motors.output_min();
failsafe_enable();
AP_Notify::flags.armed = false;
AP_Notify::flags.arming_failed = false;
return;
}
#if SPRAYER == ENABLED
// turn off sprayer's test if on
sprayer.test_pump(false);

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduPlane V3.1.1-beta"
#define THISFIRMWARE "ArduPlane V3.1.1"
/*
Lead developer: Andrew Tridgell

View File

@ -286,7 +286,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: WP_RADIUS
// @DisplayName: Waypoint Radius
// @Description: Defines the distance from a waypoint that when crossed indicates the waypoint has been completed. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete.
// @Description: Defines the maximum distance from a waypoint that when crossed indicates the waypoint may be complete. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete. Note that the navigation controller may decide to turn later than WP_RADIUS before a waypoint, based on how sharp the turn is and the speed of the aircraft. It is safe to set WP_RADIUS much larger than the usual turn radius of your aircaft and the navigation controller will work out when to turn. If you set WP_RADIUS too small then you will tend to overshoot the turns.
// @Units: Meters
// @Range: 1 32767
// @Increment: 1
@ -360,7 +360,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FENCE_AUTOENABLE
// @DisplayName: Fence automatic enable
// @Description: When set to 1, gefence automatically enables after an auto takeoff and automatically disables at the beginning of an auto landing. When on the ground before takeoff the fence is disabled.
// @Description: When set to 1, gefence automatically enables after an auto takeoff and automatically disables at the beginning of an auto landing. When on the ground before takeoff the fence is disabled. It is highly recommended to not use this option for line of sight flying and use a fence enable channel instead.
// @Values: 0:NoAutoEnable,1:AutoEnable
// @User: Standard
GSCALAR(fence_autoenable, "FENCE_AUTOENABLE", 0),

View File

@ -1,3 +1,53 @@
Release 3.1.1, September 12th 2014
----------------------------------
The ardupilot development team is proud to announce the release of
version 3.1.1 of APM:Plane. This is primarily a bugfix release with a
small number of new features.
The main bug fixed in this release is a bug that could affect saving
parameters and mission items in the FRAM/eeprom storage of
PX4v1/Pixhawk/VRBrain. The bug has been in the code since January 2013
and did not cause problems very often (which is why it hasn't been
noticed till now), but when it does happen it causes changes to
parameters or mission items not to be saved on a reboot.
Other changes in this release:
- support for using a Lidar for landing for terrain altitude (see
the RNGFND_LANDING parameter)
- improvements in the landing approach code, especially the glide
slope calculation
- added LAND_FLAP_PERCENT and TKOFF_FLAP_PCNT parameters, to control
the amount of flaps to use on takeoff and landing
- the default WP_RADIUS has been raised from 30 to 90. Note that the
L1 controller may choose to turn after the WP_RADIUS is
reached. The WP_RADIUS only controls the earliest point at which
the turn can happen, so a larger WP_RADIUS usually leads to better
flight paths, especially for faster aircraft.
- send gyro and accel status separately to the GCS (thanks to Randy)
- support setting the acceptance radius in mission waypoints (in
parameter 2), which allows for better control of waypoints where
actions such as servo release will happen
- fixed GPS time offset in HIL
- added RELAY_DEFAULT parameter, allowing control of relay state on
boot
- fixed sdcard logging on PX4v1
- added GPS_SBAS_MODE and GPS_MIN_ELEV parameters for better control
of the use of SBAS and the GPS elevation mask for advanced users
Happy flying!
Release 3.1.0, August 26th 2014
-------------------------------

View File

@ -20,6 +20,7 @@ REVERSE_THROTTLE=0
NO_REBUILD=0
START_HIL=0
TRACKER_ARGS=""
EXTERNAL_SIM=0
usage()
{
@ -45,6 +46,7 @@ Options:
for planes can choose elevon or vtail
-j NUM_PROC number of processors to use during build (default 1)
-H start HIL
-e use external simulator
mavproxy_options:
--map start with a map
@ -61,7 +63,7 @@ EOF
# parse options. Thanks to http://wiki.bash-hackers.org/howto/getopts_tutorial
while getopts ":I:VgGcj:TA:t:L:v:hwf:RNH" opt; do
while getopts ":I:VgGcj:TA:t:L:v:hwf:RNHe" opt; do
case $opt in
v)
VEHICLE=$OPTARG
@ -113,6 +115,9 @@ while getopts ":I:VgGcj:TA:t:L:v:hwf:RNH" opt; do
w)
WIPE_EEPROM=1
;;
e)
EXTERNAL_SIM=1
;;
h)
usage
exit 0
@ -302,11 +307,15 @@ trap kill_tasks SIGINT
sleep 2
rm -f $tfile
$autotest/run_in_terminal_window.sh "Simulator" $RUNSIM || {
echo "Failed to start simulator: $RUNSIM"
exit 1
}
sleep 2
if [ $EXTERNAL_SIM == 0 ]; then
$autotest/run_in_terminal_window.sh "Simulator" $RUNSIM || {
echo "Failed to start simulator: $RUNSIM"
exit 1
}
sleep 2
else
echo "Using external simulator"
fi
# mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551
options=""

View File

@ -90,10 +90,10 @@ void LinuxStorage::_storage_open(void)
void LinuxStorage::_mark_dirty(uint16_t loc, uint16_t length)
{
uint16_t end = loc + length;
while (loc < end) {
uint8_t line = (loc >> LINUX_STORAGE_LINE_SHIFT);
_dirty_mask |= 1 << line;
loc += LINUX_STORAGE_LINE_SIZE;
for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT;
line <= end>>LINUX_STORAGE_LINE_SHIFT;
line++) {
_dirty_mask |= 1U << line;
}
}

View File

@ -83,11 +83,11 @@ void LinuxStorage::_storage_open(void)
void LinuxStorage::_mark_dirty(uint16_t loc, uint16_t length)
{
uint16_t end = loc + length;
while (loc < end) {
uint8_t line = (loc >> LINUX_STORAGE_LINE_SHIFT);
_dirty_mask |= 1 << line;
loc += LINUX_STORAGE_LINE_SIZE;
}
for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT;
line <= end>>LINUX_STORAGE_LINE_SHIFT;
line++) {
_dirty_mask |= 1U << line;
}
}
void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n)

View File

@ -176,12 +176,12 @@ void PX4Storage::_storage_open(void)
*/
void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
{
uint16_t end = loc + length;
while (loc < end) {
uint8_t line = (loc >> PX4_STORAGE_LINE_SHIFT);
_dirty_mask |= 1 << line;
loc += PX4_STORAGE_LINE_SIZE;
}
uint16_t end = loc + length;
for (uint8_t line=loc>>PX4_STORAGE_LINE_SHIFT;
line <= end>>PX4_STORAGE_LINE_SHIFT;
line++) {
_dirty_mask |= 1U << line;
}
}
void PX4Storage::read_block(void *dst, uint16_t loc, size_t n)

View File

@ -177,11 +177,11 @@ void VRBRAINStorage::_storage_open(void)
void VRBRAINStorage::_mark_dirty(uint16_t loc, uint16_t length)
{
uint16_t end = loc + length;
while (loc < end) {
uint8_t line = (loc >> VRBRAIN_STORAGE_LINE_SHIFT);
_dirty_mask |= 1 << line;
loc += VRBRAIN_STORAGE_LINE_SIZE;
}
for (uint8_t line=loc>>VRBRAIN_STORAGE_LINE_SHIFT;
line <= end>>VRBRAIN_STORAGE_LINE_SHIFT;
line++) {
_dirty_mask |= 1U << line;
}
}
void VRBRAINStorage::read_block(void *dst, uint16_t loc, size_t n)

View File

@ -16,11 +16,11 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 0, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 45, 43, 45, 43, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 0, 0, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 20, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 0, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 0, 0, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 20, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 0, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 29, 12, 241, 233, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 84, 0, 0, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 49, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 0, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 84, 0, 0, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 49, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
@ -95,7 +95,7 @@ typedef enum MAV_CMD
MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */
MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */
MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */
MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama| Viewing angle vertical of panorama| */
MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */
MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters WGS84| */
MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
MAV_CMD_ENUM_END=30003, /* | */

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 14 10:56:00 2014"
#define MAVLINK_BUILD_DATE "Thu Sep 11 20:15:55 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -16,11 +16,11 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 0, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 45, 43, 45, 43, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 0, 0, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 0, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 0, 0, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 0, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 29, 12, 241, 233, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 84, 0, 0, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 49, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 0, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 84, 0, 0, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 49, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO

View File

@ -10,7 +10,7 @@ typedef struct __mavlink_battery_status_t
uint16_t voltages[10]; ///< Battery voltage of cells, in millivolts (1 = 1 millivolt)
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
uint8_t id; ///< Battery ID
uint8_t function; ///< Function of the battery
uint8_t battery_function; ///< Function of the battery
uint8_t type; ///< Type (chemistry) of the battery
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
} mavlink_battery_status_t;
@ -18,8 +18,8 @@ typedef struct __mavlink_battery_status_t
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
#define MAVLINK_MSG_ID_147_LEN 36
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 42
#define MAVLINK_MSG_ID_147_CRC 42
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
#define MAVLINK_MSG_ID_147_CRC 154
#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
@ -32,7 +32,7 @@ typedef struct __mavlink_battery_status_t
{ "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, function) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
} \
@ -46,7 +46,7 @@ typedef struct __mavlink_battery_status_t
* @param msg The MAVLink message to compress the data into
*
* @param id Battery ID
* @param function Function of the battery
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
@ -57,7 +57,7 @@ typedef struct __mavlink_battery_status_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t id, uint8_t function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, function);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
@ -78,7 +78,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.function = function;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param id Battery ID
* @param function Function of the battery
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
@ -112,7 +112,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t id,uint8_t function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, function);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.function = function;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
@ -158,7 +158,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
*/
static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
@ -172,7 +172,7 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint
*/
static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
@ -180,7 +180,7 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id,
* @param chan MAVLink channel to send the message
*
* @param id Battery ID
* @param function Function of the battery
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
@ -191,7 +191,7 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id,
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -200,7 +200,7 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, function);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
@ -216,7 +216,7 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.function = function;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
@ -236,7 +236,7 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -245,7 +245,7 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, function);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
@ -261,7 +261,7 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
packet->temperature = temperature;
packet->current_battery = current_battery;
packet->id = id;
packet->function = function;
packet->battery_function = battery_function;
packet->type = type;
packet->battery_remaining = battery_remaining;
mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
@ -290,11 +290,11 @@ static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t*
}
/**
* @brief Get field function from battery_status message
* @brief Get field battery_function from battery_status message
*
* @return Function of the battery
*/
static inline uint8_t mavlink_msg_battery_status_get_function(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
@ -384,7 +384,7 @@ static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* ms
mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages);
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
battery_status->id = mavlink_msg_battery_status_get_id(msg);
battery_status->function = mavlink_msg_battery_status_get_function(msg);
battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg);
battery_status->type = mavlink_msg_battery_status_get_type(msg);
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
#else

View File

@ -7,7 +7,7 @@ typedef struct __mavlink_global_position_int_t
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
@ -48,7 +48,7 @@ typedef struct __mavlink_global_position_int_t
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@ -186,7 +186,7 @@ static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t syste
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@ -320,7 +320,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @return Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{

View File

@ -14,21 +14,23 @@ typedef struct __mavlink_position_target_global_int_t
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
} mavlink_position_target_global_int_t;
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 43
#define MAVLINK_MSG_ID_87_LEN 43
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
#define MAVLINK_MSG_ID_87_LEN 51
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 233
#define MAVLINK_MSG_ID_87_CRC 233
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150
#define MAVLINK_MSG_ID_87_CRC 150
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
"POSITION_TARGET_GLOBAL_INT", \
12, \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
@ -39,8 +41,10 @@ typedef struct __mavlink_position_target_global_int_t
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
} \
}
@ -53,7 +57,7 @@ typedef struct __mavlink_position_target_global_int_t
*
* @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -63,10 +67,12 @@ typedef struct __mavlink_position_target_global_int_t
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
@ -80,8 +86,10 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#else
@ -96,6 +104,8 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -118,7 +128,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -128,11 +138,13 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz)
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
@ -146,8 +158,10 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#else
@ -162,6 +176,8 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -186,7 +202,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t
*/
static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
{
return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz);
return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
}
/**
@ -200,7 +216,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t sys
*/
static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
{
return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz);
return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
}
/**
@ -209,7 +225,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_
*
* @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -219,10 +235,12 @@ static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
@ -236,8 +254,10 @@ static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
@ -256,6 +276,8 @@ static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -275,7 +297,7 @@ static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -289,8 +311,10 @@ static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_messa
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
@ -309,6 +333,8 @@ static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_messa
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->coordinate_frame = coordinate_frame;
@ -343,17 +369,17 @@ static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(c
*/
static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field type_mask from position_target_global_int message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
@ -446,6 +472,26 @@ static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from position_target_global_int message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from position_target_global_int message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a position_target_global_int message into a struct
*
@ -465,6 +511,8 @@ static inline void mavlink_msg_position_target_global_int_decode(const mavlink_m
position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg);
position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg);
position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg);
position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg);
position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg);
position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg);
position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg);
#else

View File

@ -14,21 +14,23 @@ typedef struct __mavlink_position_target_local_ned_t
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
} mavlink_position_target_local_ned_t;
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 43
#define MAVLINK_MSG_ID_85_LEN 43
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
#define MAVLINK_MSG_ID_85_LEN 51
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 12
#define MAVLINK_MSG_ID_85_CRC 12
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
#define MAVLINK_MSG_ID_85_CRC 140
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
"POSITION_TARGET_LOCAL_NED", \
12, \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \
@ -39,8 +41,10 @@ typedef struct __mavlink_position_target_local_ned_t
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
} \
}
@ -53,7 +57,7 @@ typedef struct __mavlink_position_target_local_ned_t
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -63,10 +67,12 @@ typedef struct __mavlink_position_target_local_ned_t
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
@ -80,8 +86,10 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#else
@ -96,6 +104,8 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -118,7 +128,7 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -128,11 +138,13 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz)
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
@ -146,8 +158,10 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t s
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#else
@ -162,6 +176,8 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t s
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -186,7 +202,7 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t s
*/
static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
{
return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz);
return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
}
/**
@ -200,7 +216,7 @@ static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t syst
*/
static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
{
return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz);
return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
}
/**
@ -209,7 +225,7 @@ static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -219,10 +235,12 @@ static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
@ -236,8 +254,10 @@ static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
@ -256,6 +276,8 @@ static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
@ -275,7 +297,7 @@ static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -289,8 +311,10 @@ static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_messag
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
@ -309,6 +333,8 @@ static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_messag
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->coordinate_frame = coordinate_frame;
@ -343,17 +369,17 @@ static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(co
*/
static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field type_mask from position_target_local_ned message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
@ -446,6 +472,26 @@ static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from position_target_local_ned message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from position_target_local_ned message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a position_target_local_ned message into a struct
*
@ -465,6 +511,8 @@ static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_me
position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg);
position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg);
position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg);
position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg);
position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg);
position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg);
position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg);
#else

View File

@ -14,23 +14,25 @@ typedef struct __mavlink_set_position_target_global_int_t
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
} mavlink_set_position_target_global_int_t;
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 45
#define MAVLINK_MSG_ID_86_LEN 45
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
#define MAVLINK_MSG_ID_86_LEN 53
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 241
#define MAVLINK_MSG_ID_86_CRC 241
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
#define MAVLINK_MSG_ID_86_CRC 5
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
"SET_POSITION_TARGET_GLOBAL_INT", \
14, \
16, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
@ -41,10 +43,12 @@ typedef struct __mavlink_set_position_target_global_int_t
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
} \
}
@ -59,7 +63,7 @@ typedef struct __mavlink_set_position_target_global_int_t
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -69,10 +73,12 @@ typedef struct __mavlink_set_position_target_global_int_t
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
@ -86,10 +92,12 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
#else
@ -104,6 +112,8 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -130,7 +140,7 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -140,11 +150,13 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz)
uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
@ -158,10 +170,12 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
#else
@ -176,6 +190,8 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -202,7 +218,7 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint
*/
static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
{
return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz);
return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
}
/**
@ -216,7 +232,7 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t
*/
static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
{
return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz);
return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
}
/**
@ -227,7 +243,7 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(ui
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
@ -237,10 +253,12 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(ui
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
@ -254,10 +272,12 @@ static inline void mavlink_msg_set_position_target_global_int_send(mavlink_chann
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
@ -276,6 +296,8 @@ static inline void mavlink_msg_set_position_target_global_int_send(mavlink_chann
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -297,7 +319,7 @@ static inline void mavlink_msg_set_position_target_global_int_send(mavlink_chann
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -311,10 +333,12 @@ static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_m
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
@ -333,6 +357,8 @@ static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_m
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->target_system = target_system;
packet->target_component = target_component;
@ -369,7 +395,7 @@ static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_
*/
static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
@ -379,7 +405,7 @@ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_syst
*/
static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
return _MAV_RETURN_uint8_t(msg, 51);
}
/**
@ -389,17 +415,17 @@ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_comp
*/
static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 44);
return _MAV_RETURN_uint8_t(msg, 52);
}
/**
* @brief Get field type_mask from set_position_target_global_int message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
@ -492,6 +518,26 @@ static inline float mavlink_msg_set_position_target_global_int_get_afz(const mav
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from set_position_target_global_int message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from set_position_target_global_int message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a set_position_target_global_int message into a struct
*
@ -511,6 +557,8 @@ static inline void mavlink_msg_set_position_target_global_int_decode(const mavli
set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg);
set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg);
set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg);
set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg);
set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg);
set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg);
set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg);
set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg);

View File

@ -14,23 +14,25 @@ typedef struct __mavlink_set_position_target_local_ned_t
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
} mavlink_set_position_target_local_ned_t;
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 45
#define MAVLINK_MSG_ID_84_LEN 45
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53
#define MAVLINK_MSG_ID_84_LEN 53
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 29
#define MAVLINK_MSG_ID_84_CRC 29
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143
#define MAVLINK_MSG_ID_84_CRC 143
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
"SET_POSITION_TARGET_LOCAL_NED", \
14, \
16, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \
@ -41,10 +43,12 @@ typedef struct __mavlink_set_position_target_local_ned_t
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
} \
}
@ -59,7 +63,7 @@ typedef struct __mavlink_set_position_target_local_ned_t
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -69,10 +73,12 @@ typedef struct __mavlink_set_position_target_local_ned_t
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
@ -86,10 +92,12 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
#else
@ -104,6 +112,8 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -130,7 +140,7 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -140,11 +150,13 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz)
uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
@ -158,10 +170,12 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
#else
@ -176,6 +190,8 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -202,7 +218,7 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8
*/
static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
{
return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz);
return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
}
/**
@ -216,7 +232,7 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t
*/
static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
{
return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz);
return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
}
/**
@ -227,7 +243,7 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uin
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
@ -237,10 +253,12 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uin
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
@ -254,10 +272,12 @@ static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channe
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
@ -276,6 +296,8 @@ static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channe
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.target_system = target_system;
packet.target_component = target_component;
@ -297,7 +319,7 @@ static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channe
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz)
static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -311,10 +333,12 @@ static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_me
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_uint16_t(buf, 40, type_mask);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, target_component);
_mav_put_uint8_t(buf, 44, coordinate_frame);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
@ -333,6 +357,8 @@ static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_me
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->target_system = target_system;
packet->target_component = target_component;
@ -369,7 +395,7 @@ static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_m
*/
static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
@ -379,7 +405,7 @@ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_syste
*/
static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
return _MAV_RETURN_uint8_t(msg, 51);
}
/**
@ -389,17 +415,17 @@ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_compo
*/
static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 44);
return _MAV_RETURN_uint8_t(msg, 52);
}
/**
* @brief Get field type_mask from set_position_target_local_ned message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
@ -492,6 +518,26 @@ static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavl
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from set_position_target_local_ned message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from set_position_target_local_ned message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a set_position_target_local_ned message into a struct
*
@ -511,6 +557,8 @@ static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlin
set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg);
set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg);
set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg);
set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg);
set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg);
set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg);
set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg);
set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg);

View File

@ -3121,10 +3121,12 @@ static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_
}213.0,
}241.0,
}269.0,
}19315,
}3,
}70,
}137,
}297.0,
}325.0,
}19731,
}27,
}94,
}161,
};
mavlink_set_position_target_local_ned_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@ -3138,6 +3140,8 @@ static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.yaw = packet_in.yaw;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.type_mask = packet_in.type_mask;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
@ -3151,12 +3155,12 @@ static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -3169,7 +3173,7 @@ static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_local_ned_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@ -3190,8 +3194,10 @@ static void mavlink_test_position_target_local_ned(uint8_t system_id, uint8_t co
}213.0,
}241.0,
}269.0,
}19315,
}3,
}297.0,
}325.0,
}19731,
}27,
};
mavlink_position_target_local_ned_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@ -3205,6 +3211,8 @@ static void mavlink_test_position_target_local_ned(uint8_t system_id, uint8_t co
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.yaw = packet_in.yaw;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.type_mask = packet_in.type_mask;
packet1.coordinate_frame = packet_in.coordinate_frame;
@ -3216,12 +3224,12 @@ static void mavlink_test_position_target_local_ned(uint8_t system_id, uint8_t co
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_local_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_local_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -3234,7 +3242,7 @@ static void mavlink_test_position_target_local_ned(uint8_t system_id, uint8_t co
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_local_ned_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@ -3255,10 +3263,12 @@ static void mavlink_test_set_position_target_global_int(uint8_t system_id, uint8
}213.0,
}241.0,
}269.0,
}19315,
}3,
}70,
}137,
}297.0,
}325.0,
}19731,
}27,
}94,
}161,
};
mavlink_set_position_target_global_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@ -3272,6 +3282,8 @@ static void mavlink_test_set_position_target_global_int(uint8_t system_id, uint8
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.yaw = packet_in.yaw;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.type_mask = packet_in.type_mask;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
@ -3285,12 +3297,12 @@ static void mavlink_test_set_position_target_global_int(uint8_t system_id, uint8
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_global_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_global_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -3303,7 +3315,7 @@ static void mavlink_test_set_position_target_global_int(uint8_t system_id, uint8
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_set_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_set_position_target_global_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@ -3324,8 +3336,10 @@ static void mavlink_test_position_target_global_int(uint8_t system_id, uint8_t c
}213.0,
}241.0,
}269.0,
}19315,
}3,
}297.0,
}325.0,
}19731,
}27,
};
mavlink_position_target_global_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@ -3339,6 +3353,8 @@ static void mavlink_test_position_target_global_int(uint8_t system_id, uint8_t c
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.yaw = packet_in.yaw;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.type_mask = packet_in.type_mask;
packet1.coordinate_frame = packet_in.coordinate_frame;
@ -3350,12 +3366,12 @@ static void mavlink_test_position_target_global_int(uint8_t system_id, uint8_t c
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_global_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_global_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -3368,7 +3384,7 @@ static void mavlink_test_position_target_global_int(uint8_t system_id, uint8_t c
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz );
mavlink_msg_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
mavlink_msg_position_target_global_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@ -5562,7 +5578,7 @@ static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id,
packet1.temperature = packet_in.temperature;
packet1.current_battery = packet_in.current_battery;
packet1.id = packet_in.id;
packet1.function = packet_in.function;
packet1.battery_function = packet_in.battery_function;
packet1.type = packet_in.type;
packet1.battery_remaining = packet_in.battery_remaining;
@ -5575,12 +5591,12 @@ static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -5593,7 +5609,7 @@ static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_battery_status_send(MAVLINK_COMM_1 , packet1.id , packet1.function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_send(MAVLINK_COMM_1 , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 14 10:56:00 2014"
#define MAVLINK_BUILD_DATE "Thu Sep 11 20:15:55 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -1032,8 +1032,10 @@
<entry value="2800" name="MAV_CMD_PANORAMA_CREATE">
<description>Create a panorama at the current position</description>
<param index="1">Viewing angle horizontal of the panorama</param>
<param index="2">Viewing angle vertical of panorama</param>
<param index="1">Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)</param>
<param index="2">Viewing angle vertical of panorama (in degrees)</param>
<param index="3">Speed of the horizontal rotation (in degrees per second)</param>
<param index="4">Speed of the vertical rotation (in degrees per second)</param>
</entry>
<!-- VALUES FROM 0-40000 are reserved for the common message set. Values from 40000 to UINT16_MAX are available for dialects -->
@ -1612,7 +1614,7 @@
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)</field>
<field type="int32_t" name="relative_alt">Altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
@ -1889,7 +1891,7 @@
<field type="float" name="param3">PARAM3, see MAV_CMD enum</field>
<field type="float" name="param4">PARAM4, see MAV_CMD enum</field>
<field type="int32_t" name="x">PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7</field>
<field type="int32_t" name="y">PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7</field>
<field type="int32_t" name="y">PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7</field>
<field type="float" name="z">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.</field>
</message>
<message id="74" name="VFR_HUD">
@ -1974,7 +1976,7 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<field type="float" name="x">X Position in NED frame in meters</field>
<field type="float" name="y">Y Position in NED frame in meters</field>
<field type="float" name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
@ -1984,12 +1986,14 @@
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="yaw">yaw setpoint in rad</field>
<field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<message id="85" name="POSITION_TARGET_LOCAL_NED">
<description>Set vehicle position, velocity and acceleration setpoint in local frame.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<field type="float" name="x">X Position in NED frame in meters</field>
<field type="float" name="y">Y Position in NED frame in meters</field>
<field type="float" name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
@ -1999,6 +2003,8 @@
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="yaw">yaw setpoint in rad</field>
<field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<message id="86" name="SET_POSITION_TARGET_GLOBAL_INT">
<description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
@ -2006,7 +2012,7 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<field type="int32_t" name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
<field type="int32_t" name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
<field type="float" name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
@ -2016,12 +2022,14 @@
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="yaw">yaw setpoint in rad</field>
<field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<message id="87" name="POSITION_TARGET_GLOBAL_INT">
<description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
<field type="int32_t" name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
<field type="int32_t" name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
<field type="float" name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
@ -2031,6 +2039,8 @@
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
<field type="float" name="yaw">yaw setpoint in rad</field>
<field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
</message>
<message id="89" name="LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET">
<description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
@ -2450,7 +2460,7 @@
<message id="147" name="BATTERY_STATUS">
<description>Battery information</description>
<field type="uint8_t" name="id">Battery ID</field>
<field type="uint8_t" name="function" enum="MAV_BATTERY_FUNCTION">Function of the battery</field>
<field type="uint8_t" name="battery_function" enum="MAV_BATTERY_FUNCTION">Function of the battery</field>
<field type="uint8_t" name="type" enum="MAV_BATTERY_TYPE">Type (chemistry) of the battery</field>
<field type="int16_t" name="temperature">Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.</field>
<field type="uint16_t[10]" name="voltages">Battery voltage of cells, in millivolts (1 = 1 millivolt)</field>

View File

@ -194,14 +194,17 @@
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
<message id="205" name="DETECTION_STATS">
<field type="uint16_t" name="detections">Number of detections</field>
<field type="uint32_t" name="detections">Number of detections</field>
<field type="uint32_t" name="cluster_iters">Number of cluster iterations</field>
<field type="float" name="best_score">Best score</field>
<field type="int32_t" name="best_lat">Latitude of best detection * 1E7</field>
<field type="int32_t" name="best_lon">Longitude of best detection * 1E7</field>
<field type="int16_t" name="best_alt">Altitude of best detection * 1E3</field>
<field type="int32_t" name="best_detection_id">ID of best detection</field>
<field type="uint16_t" name="images_done">Number of images already processed</field>
<field type="uint16_t" name="images_todo">Number of images still to process</field>
<field type="int32_t" name="best_lat">Latitude of the best detection * 1E7</field>
<field type="int32_t" name="best_lon">Longitude of the best detection * 1E7</field>
<field type="int32_t" name="best_alt">Altitude of the best detection * 1E3</field>
<field type="uint32_t" name="best_detection_id">Best detection ID</field>
<field type="uint32_t" name="best_cluster_id">Best cluster ID</field>
<field type="uint32_t" name="best_cluster_iter_id">Best cluster ID</field>
<field type="uint32_t" name="images_done">Number of images already processed</field>
<field type="uint32_t" name="images_todo">Number of images still to process</field>
<field type="float" name="fps">Average images per seconds processed</field>
</message>
<message id="206" name="ONBOARD_HEALTH">