3 #define MAVLINK_MSG_ID_CAMERA_FEEDBACK 180
22 #define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 45
23 #define MAVLINK_MSG_ID_180_LEN 45
25 #define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC 52
26 #define MAVLINK_MSG_ID_180_CRC 52
30 #define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \
33 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \
34 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \
35 { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \
36 { "alt_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt_msl) }, \
37 { "alt_rel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, alt_rel) }, \
38 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, roll) }, \
39 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, pitch) }, \
40 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \
41 { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \
42 { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_camera_feedback_t, img_idx) }, \
43 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \
44 { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \
45 { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \
71 static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng,
float alt_msl,
float alt_rel,
float roll,
float pitch,
float yaw,
float foc_len, uint8_t
flags)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
111 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
140 mavlink_message_t* msg,
141 uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,
float alt_msl,
float alt_rel,
float roll,
float pitch,
float yaw,
float foc_len,uint8_t
flags)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
180 #if MAVLINK_CRC_EXTRA
195 static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_camera_feedback_t* camera_feedback)
197 return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->
time_usec, camera_feedback->
target_system, camera_feedback->
cam_idx, camera_feedback->
img_idx, camera_feedback->
lat, camera_feedback->
lng, camera_feedback->
alt_msl, camera_feedback->
alt_rel, camera_feedback->
roll, camera_feedback->
pitch, camera_feedback->
yaw, camera_feedback->
foc_len, camera_feedback->
flags);
209 static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_camera_feedback_t* camera_feedback)
211 return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->
time_usec, camera_feedback->
target_system, camera_feedback->
cam_idx, camera_feedback->
img_idx, camera_feedback->
lat, camera_feedback->
lng, camera_feedback->
alt_msl, camera_feedback->
alt_rel, camera_feedback->
roll, camera_feedback->
pitch, camera_feedback->
yaw, camera_feedback->
foc_len, camera_feedback->
flags);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
234 static inline void mavlink_msg_camera_feedback_send(
mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng,
float alt_msl,
float alt_rel,
float roll,
float pitch,
float yaw,
float foc_len, uint8_t flags)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
252 #if MAVLINK_CRC_EXTRA
273 #if MAVLINK_CRC_EXTRA
281 #if MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
289 static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng,
float alt_msl,
float alt_rel,
float roll,
float pitch,
float yaw,
float foc_len, uint8_t flags)
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
292 char *buf = (
char *)msgbuf;
307 #if MAVLINK_CRC_EXTRA
328 #if MAVLINK_CRC_EXTRA
347 static inline uint64_t mavlink_msg_camera_feedback_get_time_usec(
const mavlink_message_t* msg)
349 return _MAV_RETURN_uint64_t(msg, 0);
357 static inline uint8_t mavlink_msg_camera_feedback_get_target_system(
const mavlink_message_t* msg)
367 static inline uint8_t mavlink_msg_camera_feedback_get_cam_idx(
const mavlink_message_t* msg)
377 static inline uint16_t mavlink_msg_camera_feedback_get_img_idx(
const mavlink_message_t* msg)
379 return _MAV_RETURN_uint16_t(msg, 40);
387 static inline int32_t mavlink_msg_camera_feedback_get_lat(
const mavlink_message_t* msg)
389 return _MAV_RETURN_int32_t(msg, 8);
397 static inline int32_t mavlink_msg_camera_feedback_get_lng(
const mavlink_message_t* msg)
399 return _MAV_RETURN_int32_t(msg, 12);
407 static inline float mavlink_msg_camera_feedback_get_alt_msl(
const mavlink_message_t* msg)
409 return _MAV_RETURN_float(msg, 16);
417 static inline float mavlink_msg_camera_feedback_get_alt_rel(
const mavlink_message_t* msg)
419 return _MAV_RETURN_float(msg, 20);
427 static inline float mavlink_msg_camera_feedback_get_roll(
const mavlink_message_t* msg)
429 return _MAV_RETURN_float(msg, 24);
437 static inline float mavlink_msg_camera_feedback_get_pitch(
const mavlink_message_t* msg)
439 return _MAV_RETURN_float(msg, 28);
447 static inline float mavlink_msg_camera_feedback_get_yaw(
const mavlink_message_t* msg)
449 return _MAV_RETURN_float(msg, 32);
457 static inline float mavlink_msg_camera_feedback_get_foc_len(
const mavlink_message_t* msg)
459 return _MAV_RETURN_float(msg, 36);
467 static inline uint8_t mavlink_msg_camera_feedback_get_flags(
const mavlink_message_t* msg)
478 static inline void mavlink_msg_camera_feedback_decode(
const mavlink_message_t* msg,
mavlink_camera_feedback_t* camera_feedback)
480 #if MAVLINK_NEED_BYTE_SWAP
481 camera_feedback->
time_usec = mavlink_msg_camera_feedback_get_time_usec(msg);
482 camera_feedback->
lat = mavlink_msg_camera_feedback_get_lat(msg);
483 camera_feedback->
lng = mavlink_msg_camera_feedback_get_lng(msg);
484 camera_feedback->
alt_msl = mavlink_msg_camera_feedback_get_alt_msl(msg);
485 camera_feedback->
alt_rel = mavlink_msg_camera_feedback_get_alt_rel(msg);
486 camera_feedback->
roll = mavlink_msg_camera_feedback_get_roll(msg);
487 camera_feedback->
pitch = mavlink_msg_camera_feedback_get_pitch(msg);
488 camera_feedback->
yaw = mavlink_msg_camera_feedback_get_yaw(msg);
489 camera_feedback->
foc_len = mavlink_msg_camera_feedback_get_foc_len(msg);
490 camera_feedback->
img_idx = mavlink_msg_camera_feedback_get_img_idx(msg);
491 camera_feedback->
target_system = mavlink_msg_camera_feedback_get_target_system(msg);
492 camera_feedback->
cam_idx = mavlink_msg_camera_feedback_get_cam_idx(msg);
493 camera_feedback->
flags = mavlink_msg_camera_feedback_get_flags(msg);
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN
Definition: mavlink_msg_camera_feedback.h:22
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float yaw
Camera Yaw (earth frame, degrees, 0-360, true)
Definition: mavlink_msg_camera_feedback.h:14
float roll
Camera Roll angle (earth frame, degrees, +-180)
Definition: mavlink_msg_camera_feedback.h:12
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
float pitch
Camera Pitch angle (earth frame, degrees, +-180)
Definition: mavlink_msg_camera_feedback.h:13
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
uint16_t img_idx
Image index.
Definition: mavlink_msg_camera_feedback.h:16
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
int32_t lat
Latitude in (deg * 1E7)
Definition: mavlink_msg_camera_feedback.h:8
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t flags
Definition: ledstrip.h:11
Definition: mavlink_msg_camera_feedback.h:5
int16_t pitch
Definition: accelerometer.h:52
uint64_t time_usec
Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot ...
Definition: mavlink_msg_camera_feedback.h:7
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK
Definition: mavlink_msg_camera_feedback.h:3
int16_t yaw
Definition: sensors.h:31
uint8_t cam_idx
Camera ID.
Definition: mavlink_msg_camera_feedback.h:18
int32_t lng
Longitude in (deg * 1E7)
Definition: mavlink_msg_camera_feedback.h:9
float foc_len
Focal Length (mm)
Definition: mavlink_msg_camera_feedback.h:15
struct __mavlink_camera_feedback_t mavlink_camera_feedback_t
uint8_t flags
See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask.
Definition: mavlink_msg_camera_feedback.h:19
float alt_msl
Altitude Absolute (meters AMSL)
Definition: mavlink_msg_camera_feedback.h:10
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
uint8_t target_system
System ID.
Definition: mavlink_msg_camera_feedback.h:17
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
float alt_rel
Altitude Relative (meters above HOME location)
Definition: mavlink_msg_camera_feedback.h:11
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC
Definition: mavlink_msg_camera_feedback.h:25
int16_t roll
Definition: accelerometer.h:51