123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512 |
- #pragma once
- // MESSAGE CAMERA_TRACKING_IMAGE_STATUS PACKING
- #define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS 275
- typedef struct __mavlink_camera_tracking_image_status_t {
- float point_x; /*< Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
- float point_y; /*< Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
- float radius; /*< Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown*/
- float rec_top_x; /*< Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
- float rec_top_y; /*< Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
- float rec_bottom_x; /*< Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
- float rec_bottom_y; /*< Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
- uint8_t tracking_status; /*< Current tracking status*/
- uint8_t tracking_mode; /*< Current tracking mode*/
- uint8_t target_data; /*< Defines location of target data*/
- } mavlink_camera_tracking_image_status_t;
- #define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN 31
- #define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN 31
- #define MAVLINK_MSG_ID_275_LEN 31
- #define MAVLINK_MSG_ID_275_MIN_LEN 31
- #define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC 126
- #define MAVLINK_MSG_ID_275_CRC 126
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \
- 275, \
- "CAMERA_TRACKING_IMAGE_STATUS", \
- 10, \
- { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \
- { "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \
- { "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \
- { "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \
- { "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \
- { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \
- { "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \
- { "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \
- { "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \
- { "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \
- "CAMERA_TRACKING_IMAGE_STATUS", \
- 10, \
- { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \
- { "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \
- { "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \
- { "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \
- { "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \
- { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \
- { "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \
- { "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \
- { "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \
- { "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a camera_tracking_image_status message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param tracking_status Current tracking status
- * @param tracking_mode Current tracking mode
- * @param target_data Defines location of target data
- * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
- * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
- _mav_put_float(buf, 0, point_x);
- _mav_put_float(buf, 4, point_y);
- _mav_put_float(buf, 8, radius);
- _mav_put_float(buf, 12, rec_top_x);
- _mav_put_float(buf, 16, rec_top_y);
- _mav_put_float(buf, 20, rec_bottom_x);
- _mav_put_float(buf, 24, rec_bottom_y);
- _mav_put_uint8_t(buf, 28, tracking_status);
- _mav_put_uint8_t(buf, 29, tracking_mode);
- _mav_put_uint8_t(buf, 30, target_data);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #else
- mavlink_camera_tracking_image_status_t packet;
- packet.point_x = point_x;
- packet.point_y = point_y;
- packet.radius = radius;
- packet.rec_top_x = rec_top_x;
- packet.rec_top_y = rec_top_y;
- packet.rec_bottom_x = rec_bottom_x;
- packet.rec_bottom_y = rec_bottom_y;
- packet.tracking_status = tracking_status;
- packet.tracking_mode = tracking_mode;
- packet.target_data = target_data;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- }
- /**
- * @brief Pack a camera_tracking_image_status message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @param tracking_status Current tracking status
- * @param tracking_mode Current tracking mode
- * @param target_data Defines location of target data
- * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
- * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
- _mav_put_float(buf, 0, point_x);
- _mav_put_float(buf, 4, point_y);
- _mav_put_float(buf, 8, radius);
- _mav_put_float(buf, 12, rec_top_x);
- _mav_put_float(buf, 16, rec_top_y);
- _mav_put_float(buf, 20, rec_bottom_x);
- _mav_put_float(buf, 24, rec_bottom_y);
- _mav_put_uint8_t(buf, 28, tracking_status);
- _mav_put_uint8_t(buf, 29, tracking_mode);
- _mav_put_uint8_t(buf, 30, target_data);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #else
- mavlink_camera_tracking_image_status_t packet;
- packet.point_x = point_x;
- packet.point_y = point_y;
- packet.radius = radius;
- packet.rec_top_x = rec_top_x;
- packet.rec_top_y = rec_top_y;
- packet.rec_bottom_x = rec_bottom_x;
- packet.rec_bottom_y = rec_bottom_y;
- packet.tracking_status = tracking_status;
- packet.tracking_mode = tracking_mode;
- packet.target_data = target_data;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #endif
- }
- /**
- * @brief Pack a camera_tracking_image_status message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param tracking_status Current tracking status
- * @param tracking_mode Current tracking mode
- * @param target_data Defines location of target data
- * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
- * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t tracking_status,uint8_t tracking_mode,uint8_t target_data,float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
- _mav_put_float(buf, 0, point_x);
- _mav_put_float(buf, 4, point_y);
- _mav_put_float(buf, 8, radius);
- _mav_put_float(buf, 12, rec_top_x);
- _mav_put_float(buf, 16, rec_top_y);
- _mav_put_float(buf, 20, rec_bottom_x);
- _mav_put_float(buf, 24, rec_bottom_y);
- _mav_put_uint8_t(buf, 28, tracking_status);
- _mav_put_uint8_t(buf, 29, tracking_mode);
- _mav_put_uint8_t(buf, 30, target_data);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #else
- mavlink_camera_tracking_image_status_t packet;
- packet.point_x = point_x;
- packet.point_y = point_y;
- packet.radius = radius;
- packet.rec_top_x = rec_top_x;
- packet.rec_top_y = rec_top_y;
- packet.rec_bottom_x = rec_bottom_x;
- packet.rec_bottom_y = rec_bottom_y;
- packet.tracking_status = tracking_status;
- packet.tracking_mode = tracking_mode;
- packet.target_data = target_data;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- }
- /**
- * @brief Encode a camera_tracking_image_status struct
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param camera_tracking_image_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
- {
- return mavlink_msg_camera_tracking_image_status_pack(system_id, component_id, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
- }
- /**
- * @brief Encode a camera_tracking_image_status struct on a channel
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param camera_tracking_image_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
- {
- return mavlink_msg_camera_tracking_image_status_pack_chan(system_id, component_id, chan, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
- }
- /**
- * @brief Encode a camera_tracking_image_status struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param camera_tracking_image_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_camera_tracking_image_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
- {
- return mavlink_msg_camera_tracking_image_status_pack_status(system_id, component_id, _status, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
- }
- /**
- * @brief Send a camera_tracking_image_status message
- * @param chan MAVLink channel to send the message
- *
- * @param tracking_status Current tracking status
- * @param tracking_mode Current tracking mode
- * @param target_data Defines location of target data
- * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
- * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_camera_tracking_image_status_send(mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
- _mav_put_float(buf, 0, point_x);
- _mav_put_float(buf, 4, point_y);
- _mav_put_float(buf, 8, radius);
- _mav_put_float(buf, 12, rec_top_x);
- _mav_put_float(buf, 16, rec_top_y);
- _mav_put_float(buf, 20, rec_bottom_x);
- _mav_put_float(buf, 24, rec_bottom_y);
- _mav_put_uint8_t(buf, 28, tracking_status);
- _mav_put_uint8_t(buf, 29, tracking_mode);
- _mav_put_uint8_t(buf, 30, target_data);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #else
- mavlink_camera_tracking_image_status_t packet;
- packet.point_x = point_x;
- packet.point_y = point_y;
- packet.radius = radius;
- packet.rec_top_x = rec_top_x;
- packet.rec_top_y = rec_top_y;
- packet.rec_bottom_x = rec_bottom_x;
- packet.rec_bottom_y = rec_bottom_y;
- packet.tracking_status = tracking_status;
- packet.tracking_mode = tracking_mode;
- packet.target_data = target_data;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #endif
- }
- /**
- * @brief Send a camera_tracking_image_status message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_camera_tracking_image_status_send_struct(mavlink_channel_t chan, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_camera_tracking_image_status_send(chan, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)camera_tracking_image_status, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
- /*
- This variant of _send() can be used to save stack space by re-using
- memory from the receive buffer. The caller provides a
- mavlink_message_t which is the size of a full mavlink message. This
- is usually the receive buffer for the channel, and allows a reply to an
- incoming message with minimum stack space usage.
- */
- static inline void mavlink_msg_camera_tracking_image_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, point_x);
- _mav_put_float(buf, 4, point_y);
- _mav_put_float(buf, 8, radius);
- _mav_put_float(buf, 12, rec_top_x);
- _mav_put_float(buf, 16, rec_top_y);
- _mav_put_float(buf, 20, rec_bottom_x);
- _mav_put_float(buf, 24, rec_bottom_y);
- _mav_put_uint8_t(buf, 28, tracking_status);
- _mav_put_uint8_t(buf, 29, tracking_mode);
- _mav_put_uint8_t(buf, 30, target_data);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #else
- mavlink_camera_tracking_image_status_t *packet = (mavlink_camera_tracking_image_status_t *)msgbuf;
- packet->point_x = point_x;
- packet->point_y = point_y;
- packet->radius = radius;
- packet->rec_top_x = rec_top_x;
- packet->rec_top_y = rec_top_y;
- packet->rec_bottom_x = rec_bottom_x;
- packet->rec_bottom_y = rec_bottom_y;
- packet->tracking_status = tracking_status;
- packet->tracking_mode = tracking_mode;
- packet->target_data = target_data;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE CAMERA_TRACKING_IMAGE_STATUS UNPACKING
- /**
- * @brief Get field tracking_status from camera_tracking_image_status message
- *
- * @return Current tracking status
- */
- static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_status(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 28);
- }
- /**
- * @brief Get field tracking_mode from camera_tracking_image_status message
- *
- * @return Current tracking mode
- */
- static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_mode(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 29);
- }
- /**
- * @brief Get field target_data from camera_tracking_image_status message
- *
- * @return Defines location of target data
- */
- static inline uint8_t mavlink_msg_camera_tracking_image_status_get_target_data(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 30);
- }
- /**
- * @brief Get field point_x from camera_tracking_image_status message
- *
- * @return Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_point_x(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 0);
- }
- /**
- * @brief Get field point_y from camera_tracking_image_status message
- *
- * @return Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_point_y(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 4);
- }
- /**
- * @brief Get field radius from camera_tracking_image_status message
- *
- * @return Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_radius(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 8);
- }
- /**
- * @brief Get field rec_top_x from camera_tracking_image_status message
- *
- * @return Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_x(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 12);
- }
- /**
- * @brief Get field rec_top_y from camera_tracking_image_status message
- *
- * @return Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_y(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 16);
- }
- /**
- * @brief Get field rec_bottom_x from camera_tracking_image_status message
- *
- * @return Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 20);
- }
- /**
- * @brief Get field rec_bottom_y from camera_tracking_image_status message
- *
- * @return Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
- */
- static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 24);
- }
- /**
- * @brief Decode a camera_tracking_image_status message into a struct
- *
- * @param msg The message to decode
- * @param camera_tracking_image_status C-struct to decode the message contents into
- */
- static inline void mavlink_msg_camera_tracking_image_status_decode(const mavlink_message_t* msg, mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- camera_tracking_image_status->point_x = mavlink_msg_camera_tracking_image_status_get_point_x(msg);
- camera_tracking_image_status->point_y = mavlink_msg_camera_tracking_image_status_get_point_y(msg);
- camera_tracking_image_status->radius = mavlink_msg_camera_tracking_image_status_get_radius(msg);
- camera_tracking_image_status->rec_top_x = mavlink_msg_camera_tracking_image_status_get_rec_top_x(msg);
- camera_tracking_image_status->rec_top_y = mavlink_msg_camera_tracking_image_status_get_rec_top_y(msg);
- camera_tracking_image_status->rec_bottom_x = mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(msg);
- camera_tracking_image_status->rec_bottom_y = mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(msg);
- camera_tracking_image_status->tracking_status = mavlink_msg_camera_tracking_image_status_get_tracking_status(msg);
- camera_tracking_image_status->tracking_mode = mavlink_msg_camera_tracking_image_status_get_tracking_mode(msg);
- camera_tracking_image_status->target_data = mavlink_msg_camera_tracking_image_status_get_target_data(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN;
- memset(camera_tracking_image_status, 0, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
- memcpy(camera_tracking_image_status, _MAV_PAYLOAD(msg), len);
- #endif
- }
|