mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: rebuild MAVLink headers
This commit is contained in:
parent
25f6dc2549
commit
b69262b054
|
@ -16,11 +16,11 @@ extern "C" {
|
||||||
// MESSAGE LENGTHS AND CRCS
|
// MESSAGE LENGTHS AND CRCS
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_LENGTHS
|
#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
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_CRCS
|
#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
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_INFO
|
#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_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_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_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_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_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, /* | */
|
MAV_CMD_ENUM_END=30003, /* | */
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
#ifndef MAVLINK_VERSION_H
|
#ifndef MAVLINK_VERSION_H
|
||||||
#define 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_WIRE_PROTOCOL_VERSION "1.0"
|
||||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||||
|
|
||||||
|
|
|
@ -16,11 +16,11 @@ extern "C" {
|
||||||
// MESSAGE LENGTHS AND CRCS
|
// MESSAGE LENGTHS AND CRCS
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_LENGTHS
|
#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
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_CRCS
|
#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
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_INFO
|
#ifndef MAVLINK_MESSAGE_INFO
|
||||||
|
|
|
@ -10,7 +10,7 @@ typedef struct __mavlink_battery_status_t
|
||||||
uint16_t voltages[10]; ///< Battery voltage of cells, in millivolts (1 = 1 millivolt)
|
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
|
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 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
|
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
|
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
|
||||||
} mavlink_battery_status_t;
|
} 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_BATTERY_STATUS_LEN 36
|
||||||
#define MAVLINK_MSG_ID_147_LEN 36
|
#define MAVLINK_MSG_ID_147_LEN 36
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 42
|
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
|
||||||
#define MAVLINK_MSG_ID_147_CRC 42
|
#define MAVLINK_MSG_ID_147_CRC 154
|
||||||
|
|
||||||
#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
|
#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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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 msg The MAVLink message to compress the data into
|
||||||
*
|
*
|
||||||
* @param id Battery ID
|
* @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 type Type (chemistry) of the battery
|
||||||
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
|
* @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)
|
* @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)
|
* @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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
|
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, 8, temperature);
|
||||||
_mav_put_int16_t(buf, 30, current_battery);
|
_mav_put_int16_t(buf, 30, current_battery);
|
||||||
_mav_put_uint8_t(buf, 32, id);
|
_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_uint8_t(buf, 34, type);
|
||||||
_mav_put_int8_t(buf, 35, battery_remaining);
|
_mav_put_int8_t(buf, 35, battery_remaining);
|
||||||
_mav_put_uint16_t_array(buf, 10, voltages, 10);
|
_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.temperature = temperature;
|
||||||
packet.current_battery = current_battery;
|
packet.current_battery = current_battery;
|
||||||
packet.id = id;
|
packet.id = id;
|
||||||
packet.function = function;
|
packet.battery_function = battery_function;
|
||||||
packet.type = type;
|
packet.type = type;
|
||||||
packet.battery_remaining = battery_remaining;
|
packet.battery_remaining = battery_remaining;
|
||||||
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
|
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 chan The MAVLink channel this message will be sent over
|
||||||
* @param msg The MAVLink message to compress the data into
|
* @param msg The MAVLink message to compress the data into
|
||||||
* @param id Battery ID
|
* @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 type Type (chemistry) of the battery
|
||||||
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
|
* @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)
|
* @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,
|
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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
|
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, 8, temperature);
|
||||||
_mav_put_int16_t(buf, 30, current_battery);
|
_mav_put_int16_t(buf, 30, current_battery);
|
||||||
_mav_put_uint8_t(buf, 32, id);
|
_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_uint8_t(buf, 34, type);
|
||||||
_mav_put_int8_t(buf, 35, battery_remaining);
|
_mav_put_int8_t(buf, 35, battery_remaining);
|
||||||
_mav_put_uint16_t_array(buf, 10, voltages, 10);
|
_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.temperature = temperature;
|
||||||
packet.current_battery = current_battery;
|
packet.current_battery = current_battery;
|
||||||
packet.id = id;
|
packet.id = id;
|
||||||
packet.function = function;
|
packet.battery_function = battery_function;
|
||||||
packet.type = type;
|
packet.type = type;
|
||||||
packet.battery_remaining = battery_remaining;
|
packet.battery_remaining = battery_remaining;
|
||||||
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
|
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)
|
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)
|
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 chan MAVLink channel to send the message
|
||||||
*
|
*
|
||||||
* @param id Battery ID
|
* @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 type Type (chemistry) of the battery
|
||||||
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
|
* @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)
|
* @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
|
#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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
|
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, 8, temperature);
|
||||||
_mav_put_int16_t(buf, 30, current_battery);
|
_mav_put_int16_t(buf, 30, current_battery);
|
||||||
_mav_put_uint8_t(buf, 32, id);
|
_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_uint8_t(buf, 34, type);
|
||||||
_mav_put_int8_t(buf, 35, battery_remaining);
|
_mav_put_int8_t(buf, 35, battery_remaining);
|
||||||
_mav_put_uint16_t_array(buf, 10, voltages, 10);
|
_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.temperature = temperature;
|
||||||
packet.current_battery = current_battery;
|
packet.current_battery = current_battery;
|
||||||
packet.id = id;
|
packet.id = id;
|
||||||
packet.function = function;
|
packet.battery_function = battery_function;
|
||||||
packet.type = type;
|
packet.type = type;
|
||||||
packet.battery_remaining = battery_remaining;
|
packet.battery_remaining = battery_remaining;
|
||||||
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
|
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
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
incoming message with minimum stack space usage.
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char *buf = (char *)msgbuf;
|
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, 8, temperature);
|
||||||
_mav_put_int16_t(buf, 30, current_battery);
|
_mav_put_int16_t(buf, 30, current_battery);
|
||||||
_mav_put_uint8_t(buf, 32, id);
|
_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_uint8_t(buf, 34, type);
|
||||||
_mav_put_int8_t(buf, 35, battery_remaining);
|
_mav_put_int8_t(buf, 35, battery_remaining);
|
||||||
_mav_put_uint16_t_array(buf, 10, voltages, 10);
|
_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->temperature = temperature;
|
||||||
packet->current_battery = current_battery;
|
packet->current_battery = current_battery;
|
||||||
packet->id = id;
|
packet->id = id;
|
||||||
packet->function = function;
|
packet->battery_function = battery_function;
|
||||||
packet->type = type;
|
packet->type = type;
|
||||||
packet->battery_remaining = battery_remaining;
|
packet->battery_remaining = battery_remaining;
|
||||||
mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
|
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
|
* @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);
|
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);
|
mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages);
|
||||||
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
|
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
|
||||||
battery_status->id = mavlink_msg_battery_status_get_id(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->type = mavlink_msg_battery_status_get_type(msg);
|
||||||
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
|
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -7,7 +7,7 @@ typedef struct __mavlink_global_position_int_t
|
||||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||||
int32_t lat; ///< Latitude, expressed as * 1E7
|
int32_t lat; ///< Latitude, expressed as * 1E7
|
||||||
int32_t lon; ///< Longitude, 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)
|
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 vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
|
||||||
int16_t vy; ///< Ground Y Speed (Longitude), 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 time_boot_ms Timestamp (milliseconds since system boot)
|
||||||
* @param lat Latitude, expressed as * 1E7
|
* @param lat Latitude, expressed as * 1E7
|
||||||
* @param lon Longitude, 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 relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||||
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
||||||
* @param vy Ground Y Speed (Longitude), 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 time_boot_ms Timestamp (milliseconds since system boot)
|
||||||
* @param lat Latitude, expressed as * 1E7
|
* @param lat Latitude, expressed as * 1E7
|
||||||
* @param lon Longitude, 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 relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||||
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
||||||
* @param vy Ground Y Speed (Longitude), 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 time_boot_ms Timestamp (milliseconds since system boot)
|
||||||
* @param lat Latitude, expressed as * 1E7
|
* @param lat Latitude, expressed as * 1E7
|
||||||
* @param lon Longitude, 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 relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||||
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
|
||||||
* @param vy Ground Y Speed (Longitude), 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
|
* @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)
|
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
|
|
|
@ -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 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 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
|
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
|
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;
|
} mavlink_position_target_global_int_t;
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 43
|
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
|
||||||
#define MAVLINK_MSG_ID_87_LEN 43
|
#define MAVLINK_MSG_ID_87_LEN 51
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 233
|
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150
|
||||||
#define MAVLINK_MSG_ID_87_CRC 233
|
#define MAVLINK_MSG_ID_87_CRC 150
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
|
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
|
||||||
"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) }, \
|
{ { "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
|
||||||
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
|
{ "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 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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)
|
* @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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -96,6 +104,8 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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 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 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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)
|
* @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,
|
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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -162,6 +176,8 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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)
|
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)
|
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 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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
|
#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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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
|
#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);
|
_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.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
incoming message with minimum stack space usage.
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char *buf = (char *)msgbuf;
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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
|
#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);
|
_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->afx = afx;
|
||||||
packet->afy = afy;
|
packet->afy = afy;
|
||||||
packet->afz = afz;
|
packet->afz = afz;
|
||||||
|
packet->yaw = yaw;
|
||||||
|
packet->yaw_rate = yaw_rate;
|
||||||
packet->type_mask = type_mask;
|
packet->type_mask = type_mask;
|
||||||
packet->coordinate_frame = coordinate_frame;
|
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)
|
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
|
* @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)
|
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);
|
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
|
* @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->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->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->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->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);
|
position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg);
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -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 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 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
|
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
|
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;
|
} mavlink_position_target_local_ned_t;
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 43
|
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
|
||||||
#define MAVLINK_MSG_ID_85_LEN 43
|
#define MAVLINK_MSG_ID_85_LEN 51
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 12
|
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
|
||||||
#define MAVLINK_MSG_ID_85_CRC 12
|
#define MAVLINK_MSG_ID_85_CRC 140
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
|
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
|
||||||
"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) }, \
|
{ { "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
|
||||||
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
|
{ "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 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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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)
|
* @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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -96,6 +104,8 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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 msg The MAVLink message to compress the data into
|
||||||
* @param time_boot_ms Timestamp in milliseconds since system boot
|
* @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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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)
|
* @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,
|
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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -162,6 +176,8 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t s
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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)
|
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)
|
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 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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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
|
#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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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
|
#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);
|
_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.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.coordinate_frame = coordinate_frame;
|
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
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
incoming message with minimum stack space usage.
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char *buf = (char *)msgbuf;
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, coordinate_frame);
|
_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
|
#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);
|
_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->afx = afx;
|
||||||
packet->afy = afy;
|
packet->afy = afy;
|
||||||
packet->afz = afz;
|
packet->afz = afz;
|
||||||
|
packet->yaw = yaw;
|
||||||
|
packet->yaw_rate = yaw_rate;
|
||||||
packet->type_mask = type_mask;
|
packet->type_mask = type_mask;
|
||||||
packet->coordinate_frame = coordinate_frame;
|
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)
|
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
|
* @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)
|
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);
|
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
|
* @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->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->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->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->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);
|
position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg);
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -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 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 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
|
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_system; ///< System ID
|
||||||
uint8_t target_component; ///< Component 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
|
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;
|
} mavlink_set_position_target_global_int_t;
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 45
|
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
|
||||||
#define MAVLINK_MSG_ID_86_LEN 45
|
#define MAVLINK_MSG_ID_86_LEN 53
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 241
|
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
|
||||||
#define MAVLINK_MSG_ID_86_CRC 241
|
#define MAVLINK_MSG_ID_86_CRC 5
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
|
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
|
||||||
"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) }, \
|
{ { "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
|
||||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
|
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
|
||||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
|
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
|
||||||
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
|
{ "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_system System ID
|
||||||
* @param target_component Component 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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)
|
* @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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -104,6 +112,8 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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_system System ID
|
||||||
* @param target_component Component 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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)
|
* @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,
|
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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -176,6 +190,8 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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)
|
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)
|
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_system System ID
|
||||||
* @param target_component Component 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 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 lat_int X Position in WGS84 frame in 1e7 * meters
|
||||||
* @param lon_int Y 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
|
* @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 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 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 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
|
#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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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
|
#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);
|
_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.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
incoming message with minimum stack space usage.
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char *buf = (char *)msgbuf;
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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
|
#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);
|
_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->afx = afx;
|
||||||
packet->afy = afy;
|
packet->afy = afy;
|
||||||
packet->afz = afz;
|
packet->afz = afz;
|
||||||
|
packet->yaw = yaw;
|
||||||
|
packet->yaw_rate = yaw_rate;
|
||||||
packet->type_mask = type_mask;
|
packet->type_mask = type_mask;
|
||||||
packet->target_system = target_system;
|
packet->target_system = target_system;
|
||||||
packet->target_component = target_component;
|
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)
|
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)
|
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)
|
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
|
* @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)
|
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);
|
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
|
* @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->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->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->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->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_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);
|
set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg);
|
||||||
|
|
|
@ -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 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 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
|
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_system; ///< System ID
|
||||||
uint8_t target_component; ///< Component 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
|
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;
|
} mavlink_set_position_target_local_ned_t;
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 45
|
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53
|
||||||
#define MAVLINK_MSG_ID_84_LEN 45
|
#define MAVLINK_MSG_ID_84_LEN 53
|
||||||
|
|
||||||
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 29
|
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143
|
||||||
#define MAVLINK_MSG_ID_84_CRC 29
|
#define MAVLINK_MSG_ID_84_CRC 143
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
|
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
|
||||||
"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) }, \
|
{ { "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "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) }, \
|
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \
|
||||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
|
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \
|
||||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
|
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
|
||||||
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
|
{ "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_system System ID
|
||||||
* @param target_component Component 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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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)
|
* @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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -104,6 +112,8 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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_system System ID
|
||||||
* @param target_component Component 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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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)
|
* @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,
|
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,
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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);
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
|
||||||
#else
|
#else
|
||||||
|
@ -176,6 +190,8 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8
|
||||||
packet.afx = afx;
|
packet.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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)
|
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)
|
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_system System ID
|
||||||
* @param target_component Component 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 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 x X Position in NED frame in meters
|
||||||
* @param y Y 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)
|
* @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 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 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 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
|
#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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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
|
#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);
|
_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.afx = afx;
|
||||||
packet.afy = afy;
|
packet.afy = afy;
|
||||||
packet.afz = afz;
|
packet.afz = afz;
|
||||||
|
packet.yaw = yaw;
|
||||||
|
packet.yaw_rate = yaw_rate;
|
||||||
packet.type_mask = type_mask;
|
packet.type_mask = type_mask;
|
||||||
packet.target_system = target_system;
|
packet.target_system = target_system;
|
||||||
packet.target_component = target_component;
|
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
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
incoming message with minimum stack space usage.
|
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
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
char *buf = (char *)msgbuf;
|
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, 28, afx);
|
||||||
_mav_put_float(buf, 32, afy);
|
_mav_put_float(buf, 32, afy);
|
||||||
_mav_put_float(buf, 36, afz);
|
_mav_put_float(buf, 36, afz);
|
||||||
_mav_put_uint16_t(buf, 40, type_mask);
|
_mav_put_float(buf, 40, yaw);
|
||||||
_mav_put_uint8_t(buf, 42, target_system);
|
_mav_put_float(buf, 44, yaw_rate);
|
||||||
_mav_put_uint8_t(buf, 43, target_component);
|
_mav_put_uint16_t(buf, 48, type_mask);
|
||||||
_mav_put_uint8_t(buf, 44, coordinate_frame);
|
_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
|
#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);
|
_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->afx = afx;
|
||||||
packet->afy = afy;
|
packet->afy = afy;
|
||||||
packet->afz = afz;
|
packet->afz = afz;
|
||||||
|
packet->yaw = yaw;
|
||||||
|
packet->yaw_rate = yaw_rate;
|
||||||
packet->type_mask = type_mask;
|
packet->type_mask = type_mask;
|
||||||
packet->target_system = target_system;
|
packet->target_system = target_system;
|
||||||
packet->target_component = target_component;
|
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)
|
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)
|
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)
|
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
|
* @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)
|
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);
|
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
|
* @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->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->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->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->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_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);
|
set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg);
|
||||||
|
|
|
@ -3121,10 +3121,12 @@ static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_
|
||||||
}213.0,
|
}213.0,
|
||||||
}241.0,
|
}241.0,
|
||||||
}269.0,
|
}269.0,
|
||||||
}19315,
|
}297.0,
|
||||||
}3,
|
}325.0,
|
||||||
}70,
|
}19731,
|
||||||
}137,
|
}27,
|
||||||
|
}94,
|
||||||
|
}161,
|
||||||
};
|
};
|
||||||
mavlink_set_position_target_local_ned_t packet1, packet2;
|
mavlink_set_position_target_local_ned_t packet1, packet2;
|
||||||
memset(&packet1, 0, sizeof(packet1));
|
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.afx = packet_in.afx;
|
||||||
packet1.afy = packet_in.afy;
|
packet1.afy = packet_in.afy;
|
||||||
packet1.afz = packet_in.afz;
|
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.type_mask = packet_in.type_mask;
|
||||||
packet1.target_system = packet_in.target_system;
|
packet1.target_system = packet_in.target_system;
|
||||||
packet1.target_component = packet_in.target_component;
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_local_ned_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_local_ned_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_local_ned_decode(last_msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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,
|
}213.0,
|
||||||
}241.0,
|
}241.0,
|
||||||
}269.0,
|
}269.0,
|
||||||
}19315,
|
}297.0,
|
||||||
}3,
|
}325.0,
|
||||||
|
}19731,
|
||||||
|
}27,
|
||||||
};
|
};
|
||||||
mavlink_position_target_local_ned_t packet1, packet2;
|
mavlink_position_target_local_ned_t packet1, packet2;
|
||||||
memset(&packet1, 0, sizeof(packet1));
|
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.afx = packet_in.afx;
|
||||||
packet1.afy = packet_in.afy;
|
packet1.afy = packet_in.afy;
|
||||||
packet1.afz = packet_in.afz;
|
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.type_mask = packet_in.type_mask;
|
||||||
packet1.coordinate_frame = packet_in.coordinate_frame;
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_local_ned_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_local_ned_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_local_ned_decode(last_msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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,
|
}213.0,
|
||||||
}241.0,
|
}241.0,
|
||||||
}269.0,
|
}269.0,
|
||||||
}19315,
|
}297.0,
|
||||||
}3,
|
}325.0,
|
||||||
}70,
|
}19731,
|
||||||
}137,
|
}27,
|
||||||
|
}94,
|
||||||
|
}161,
|
||||||
};
|
};
|
||||||
mavlink_set_position_target_global_int_t packet1, packet2;
|
mavlink_set_position_target_global_int_t packet1, packet2;
|
||||||
memset(&packet1, 0, sizeof(packet1));
|
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.afx = packet_in.afx;
|
||||||
packet1.afy = packet_in.afy;
|
packet1.afy = packet_in.afy;
|
||||||
packet1.afz = packet_in.afz;
|
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.type_mask = packet_in.type_mask;
|
||||||
packet1.target_system = packet_in.target_system;
|
packet1.target_system = packet_in.target_system;
|
||||||
packet1.target_component = packet_in.target_component;
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_global_int_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_global_int_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_set_position_target_global_int_decode(last_msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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,
|
}213.0,
|
||||||
}241.0,
|
}241.0,
|
||||||
}269.0,
|
}269.0,
|
||||||
}19315,
|
}297.0,
|
||||||
}3,
|
}325.0,
|
||||||
|
}19731,
|
||||||
|
}27,
|
||||||
};
|
};
|
||||||
mavlink_position_target_global_int_t packet1, packet2;
|
mavlink_position_target_global_int_t packet1, packet2;
|
||||||
memset(&packet1, 0, sizeof(packet1));
|
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.afx = packet_in.afx;
|
||||||
packet1.afy = packet_in.afy;
|
packet1.afy = packet_in.afy;
|
||||||
packet1.afz = packet_in.afz;
|
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.type_mask = packet_in.type_mask;
|
||||||
packet1.coordinate_frame = packet_in.coordinate_frame;
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_global_int_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_global_int_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_position_target_global_int_decode(last_msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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.temperature = packet_in.temperature;
|
||||||
packet1.current_battery = packet_in.current_battery;
|
packet1.current_battery = packet_in.current_battery;
|
||||||
packet1.id = packet_in.id;
|
packet1.id = packet_in.id;
|
||||||
packet1.function = packet_in.function;
|
packet1.battery_function = packet_in.battery_function;
|
||||||
packet1.type = packet_in.type;
|
packet1.type = packet_in.type;
|
||||||
packet1.battery_remaining = packet_in.battery_remaining;
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_battery_status_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_battery_status_decode(&msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
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);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
memset(&packet2, 0, sizeof(packet2));
|
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_msg_battery_status_decode(last_msg, &packet2);
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
}
|
}
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
#ifndef MAVLINK_VERSION_H
|
#ifndef MAVLINK_VERSION_H
|
||||||
#define 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_WIRE_PROTOCOL_VERSION "1.0"
|
||||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue