3 #define MAVLINK_MSG_ID_BRIEF_FEATURE 195 
   17 #define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53 
   18 #define MAVLINK_MSG_ID_195_LEN 53 
   20 #define MAVLINK_MSG_ID_BRIEF_FEATURE_CRC 88 
   21 #define MAVLINK_MSG_ID_195_CRC 88 
   23 #define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32 
   25 #define MAVLINK_MESSAGE_INFO_BRIEF_FEATURE { \ 
   28     {  { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_brief_feature_t, x) }, \ 
   29          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_brief_feature_t, y) }, \ 
   30          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_brief_feature_t, z) }, \ 
   31          { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_brief_feature_t, response) }, \ 
   32          { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_brief_feature_t, size) }, \ 
   33          { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_brief_feature_t, orientation) }, \ 
   34          { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \ 
   35          { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_brief_feature_t, descriptor) }, \ 
   56 static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
 
   57                                float x, 
float y, 
float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, 
const uint8_t *descriptor, 
float response)
 
   59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
   68     _mav_put_uint8_t_array(buf, 21, descriptor, 32);
 
   79     mav_array_memcpy(packet.
descriptor, descriptor, 
sizeof(uint8_t)*32);
 
  107 static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
 
  108                                mavlink_message_t* msg,
 
  109                                    float x,
float y,
float z,uint8_t orientation_assignment,uint16_t size,uint16_t orientation,
const uint8_t *descriptor,
float response)
 
  111 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  120     _mav_put_uint8_t_array(buf, 21, descriptor, 32);
 
  131     mav_array_memcpy(packet.
descriptor, descriptor, 
sizeof(uint8_t)*32);
 
  136 #if MAVLINK_CRC_EXTRA 
  151 static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 
const mavlink_brief_feature_t* brief_feature)
 
  153     return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->
x, brief_feature->
y, brief_feature->
z, brief_feature->
orientation_assignment, brief_feature->
size, brief_feature->
orientation, brief_feature->
descriptor, brief_feature->
response);
 
  165 static inline uint16_t mavlink_msg_brief_feature_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 
const mavlink_brief_feature_t* brief_feature)
 
  167     return mavlink_msg_brief_feature_pack_chan(system_id, component_id, chan, msg, brief_feature->
x, brief_feature->
y, brief_feature->
z, brief_feature->
orientation_assignment, brief_feature->
size, brief_feature->
orientation, brief_feature->
descriptor, brief_feature->
response);
 
  183 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 
  185 static inline void mavlink_msg_brief_feature_send(
mavlink_channel_t chan, 
float x, 
float y, 
float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, 
const uint8_t *descriptor, 
float response)
 
  187 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  196     _mav_put_uint8_t_array(buf, 21, descriptor, 32);
 
  197 #if MAVLINK_CRC_EXTRA 
  211     mav_array_memcpy(packet.
descriptor, descriptor, 
sizeof(uint8_t)*32);
 
  212 #if MAVLINK_CRC_EXTRA 
  220 #if MAVLINK_MSG_ID_BRIEF_FEATURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN 
  228 static inline void mavlink_msg_brief_feature_send_buf(mavlink_message_t *msgbuf, 
mavlink_channel_t chan,  
float x, 
float y, 
float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, 
const uint8_t *descriptor, 
float response)
 
  230 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  231     char *buf = (
char *)msgbuf;
 
  239     _mav_put_uint8_t_array(buf, 21, descriptor, 32);
 
  240 #if MAVLINK_CRC_EXTRA 
  254     mav_array_memcpy(packet->
descriptor, descriptor, 
sizeof(uint8_t)*32);
 
  255 #if MAVLINK_CRC_EXTRA 
  274 static inline float mavlink_msg_brief_feature_get_x(
const mavlink_message_t* msg)
 
  276     return _MAV_RETURN_float(msg,  0);
 
  284 static inline float mavlink_msg_brief_feature_get_y(
const mavlink_message_t* msg)
 
  286     return _MAV_RETURN_float(msg,  4);
 
  294 static inline float mavlink_msg_brief_feature_get_z(
const mavlink_message_t* msg)
 
  296     return _MAV_RETURN_float(msg,  8);
 
  304 static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(
const mavlink_message_t* msg)
 
  314 static inline uint16_t mavlink_msg_brief_feature_get_size(
const mavlink_message_t* msg)
 
  316     return _MAV_RETURN_uint16_t(msg,  16);
 
  324 static inline uint16_t mavlink_msg_brief_feature_get_orientation(
const mavlink_message_t* msg)
 
  326     return _MAV_RETURN_uint16_t(msg,  18);
 
  334 static inline uint16_t mavlink_msg_brief_feature_get_descriptor(
const mavlink_message_t* msg, uint8_t *descriptor)
 
  336     return _MAV_RETURN_uint8_t_array(msg, descriptor, 32,  21);
 
  344 static inline float mavlink_msg_brief_feature_get_response(
const mavlink_message_t* msg)
 
  346     return _MAV_RETURN_float(msg,  12);
 
  355 static inline void mavlink_msg_brief_feature_decode(
const mavlink_message_t* msg, 
mavlink_brief_feature_t* brief_feature)
 
  357 #if MAVLINK_NEED_BYTE_SWAP 
  358     brief_feature->
x = mavlink_msg_brief_feature_get_x(msg);
 
  359     brief_feature->
y = mavlink_msg_brief_feature_get_y(msg);
 
  360     brief_feature->
z = mavlink_msg_brief_feature_get_z(msg);
 
  361     brief_feature->
response = mavlink_msg_brief_feature_get_response(msg);
 
  362     brief_feature->
size = mavlink_msg_brief_feature_get_size(msg);
 
  363     brief_feature->
orientation = mavlink_msg_brief_feature_get_orientation(msg);
 
  365     mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->
descriptor);
 
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
struct __mavlink_brief_feature_t mavlink_brief_feature_t
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
float x
x position in m 
Definition: mavlink_msg_brief_feature.h:7
uint8_t descriptor[32]
Descriptor. 
Definition: mavlink_msg_brief_feature.h:14
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
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
float z
z position in m 
Definition: mavlink_msg_brief_feature.h:9
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
uint16_t orientation
Orientation. 
Definition: mavlink_msg_brief_feature.h:12
mavlink_channel_t
Definition: mavlink_types.h:178
Definition: mavlink_msg_brief_feature.h:5
uint8_t orientation_assignment
Orientation assignment 0: false, 1:true. 
Definition: mavlink_msg_brief_feature.h:13
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t size
Size in pixels. 
Definition: mavlink_msg_brief_feature.h:11
float response
Harris operator response at this location. 
Definition: mavlink_msg_brief_feature.h:10
#define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN
Definition: mavlink_msg_brief_feature.h:17
uint8_t z
set the acc deadband for z-Axis, this ignores small accelerations 
Definition: accelerometer.h:52
#define MAVLINK_MSG_ID_BRIEF_FEATURE
Definition: mavlink_msg_brief_feature.h:3
float y
y position in m 
Definition: mavlink_msg_brief_feature.h:8
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
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
#define MAVLINK_MSG_ID_BRIEF_FEATURE_CRC
Definition: mavlink_msg_brief_feature.h:20