00001
00002
00003 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140
00004
00005 typedef struct __mavlink_actuator_control_target_t
00006 {
00007 uint64_t time_usec;
00008 float controls[8];
00009 uint8_t group_mlx;
00010 } mavlink_actuator_control_target_t;
00011
00012 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41
00013 #define MAVLINK_MSG_ID_140_LEN 41
00014
00015 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181
00016 #define MAVLINK_MSG_ID_140_CRC 181
00017
00018 #define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8
00019
00020 #define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \
00021 "ACTUATOR_CONTROL_TARGET", \
00022 3, \
00023 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \
00024 { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
00025 { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \
00026 } \
00027 }
00028
00029
00041 static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00042 uint64_t time_usec, uint8_t group_mlx, const float *controls)
00043 {
00044 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00045 char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
00046 _mav_put_uint64_t(buf, 0, time_usec);
00047 _mav_put_uint8_t(buf, 40, group_mlx);
00048 _mav_put_float_array(buf, 8, controls, 8);
00049 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00050 #else
00051 mavlink_actuator_control_target_t packet;
00052 packet.time_usec = time_usec;
00053 packet.group_mlx = group_mlx;
00054 mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
00055 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00056 #endif
00057
00058 msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET;
00059 #if MAVLINK_CRC_EXTRA
00060 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00061 #else
00062 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00063 #endif
00064 }
00065
00077 static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00078 mavlink_message_t* msg,
00079 uint64_t time_usec,uint8_t group_mlx,const float *controls)
00080 {
00081 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00082 char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
00083 _mav_put_uint64_t(buf, 0, time_usec);
00084 _mav_put_uint8_t(buf, 40, group_mlx);
00085 _mav_put_float_array(buf, 8, controls, 8);
00086 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00087 #else
00088 mavlink_actuator_control_target_t packet;
00089 packet.time_usec = time_usec;
00090 packet.group_mlx = group_mlx;
00091 mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
00092 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00093 #endif
00094
00095 msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET;
00096 #if MAVLINK_CRC_EXTRA
00097 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00098 #else
00099 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00100 #endif
00101 }
00102
00111 static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target)
00112 {
00113 return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls);
00114 }
00115
00125 static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target)
00126 {
00127 return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls);
00128 }
00129
00138 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00139
00140 static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls)
00141 {
00142 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00143 char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
00144 _mav_put_uint64_t(buf, 0, time_usec);
00145 _mav_put_uint8_t(buf, 40, group_mlx);
00146 _mav_put_float_array(buf, 8, controls, 8);
00147 #if MAVLINK_CRC_EXTRA
00148 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00149 #else
00150 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00151 #endif
00152 #else
00153 mavlink_actuator_control_target_t packet;
00154 packet.time_usec = time_usec;
00155 packet.group_mlx = group_mlx;
00156 mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
00157 #if MAVLINK_CRC_EXTRA
00158 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00159 #else
00160 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00161 #endif
00162 #endif
00163 }
00164
00165 #if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00166
00167
00168
00169
00170
00171
00172
00173 static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls)
00174 {
00175 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00176 char *buf = (char *)msgbuf;
00177 _mav_put_uint64_t(buf, 0, time_usec);
00178 _mav_put_uint8_t(buf, 40, group_mlx);
00179 _mav_put_float_array(buf, 8, controls, 8);
00180 #if MAVLINK_CRC_EXTRA
00181 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00182 #else
00183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00184 #endif
00185 #else
00186 mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf;
00187 packet->time_usec = time_usec;
00188 packet->group_mlx = group_mlx;
00189 mav_array_memcpy(packet->controls, controls, sizeof(float)*8);
00190 #if MAVLINK_CRC_EXTRA
00191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
00192 #else
00193 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00194 #endif
00195 #endif
00196 }
00197 #endif
00198
00199 #endif
00200
00201
00202
00203
00209 static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg)
00210 {
00211 return _MAV_RETURN_uint64_t(msg, 0);
00212 }
00213
00219 static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg)
00220 {
00221 return _MAV_RETURN_uint8_t(msg, 40);
00222 }
00223
00229 static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls)
00230 {
00231 return _MAV_RETURN_float_array(msg, controls, 8, 8);
00232 }
00233
00240 static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target)
00241 {
00242 #if MAVLINK_NEED_BYTE_SWAP
00243 actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg);
00244 mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls);
00245 actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg);
00246 #else
00247 memcpy(actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
00248 #endif
00249 }