GCS_MAVLink: rebuild MAVLink headers

This commit is contained in:
Andrew Tridgell 2014-07-24 21:37:41 +10:00
parent 3d2460bd42
commit 8ef9aa0300
8 changed files with 457 additions and 22 deletions

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 9 17:11:13 2014"
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:34:30 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -73,7 +73,7 @@ static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {

File diff suppressed because one or more lines are too long

View File

@ -3367,6 +3367,201 @@ static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_attitude_setpoint_external(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_setpoint_external_t packet_in = {
963497464,
}{ 45.0, 46.0, 47.0, 48.0 },
}157.0,
}185.0,
}213.0,
}241.0,
}113,
}180,
}247,
};
mavlink_attitude_setpoint_external_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.body_roll_rate = packet_in.body_roll_rate;
packet1.body_pitch_rate = packet_in.body_pitch_rate;
packet1.body_yaw_rate = packet_in.body_yaw_rate;
packet1.thrust = packet_in.thrust;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.type_mask = packet_in.type_mask;
mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_setpoint_external_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_setpoint_external_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_setpoint_external_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_attitude_setpoint_external_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_setpoint_external_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
mavlink_msg_attitude_setpoint_external_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_local_ned_position_setpoint_external(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_ned_position_setpoint_external_t packet_in = {
963497464,
}45.0,
}73.0,
}101.0,
}129.0,
}157.0,
}185.0,
}213.0,
}241.0,
}269.0,
}19315,
}3,
}70,
}137,
};
mavlink_local_ned_position_setpoint_external_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.type_mask = packet_in.type_mask;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.coordinate_frame = packet_in.coordinate_frame;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_ned_position_setpoint_external_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_ned_position_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_ned_position_setpoint_external_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_local_ned_position_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_ned_position_setpoint_external_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_local_ned_position_setpoint_external_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_ned_position_setpoint_external_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_ned_position_setpoint_external_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_local_ned_position_setpoint_external_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_global_position_setpoint_external_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_setpoint_external_int_t packet_in = {
963497464,
}963497672,
}963497880,
}101.0,
}129.0,
}157.0,
}185.0,
}213.0,
}241.0,
}269.0,
}19315,
}3,
}70,
};
mavlink_global_position_setpoint_external_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.lat_int = packet_in.lat_int;
packet1.lon_int = packet_in.lon_int;
packet1.alt = packet_in.alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.afx = packet_in.afx;
packet1.afy = packet_in.afy;
packet1.afz = packet_in.afz;
packet1.type_mask = packet_in.type_mask;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_external_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_position_setpoint_external_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , 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_global_position_setpoint_external_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , 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_global_position_setpoint_external_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_position_setpoint_external_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_external_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , 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_global_position_setpoint_external_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -5427,6 +5622,204 @@ static void mavlink_test_distance_sensor(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_terrain_request(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_terrain_request_t packet_in = {
93372036854775807ULL,
}963497880,
}963498088,
}18067,
};
mavlink_terrain_request_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.mask = packet_in.mask;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.grid_spacing = packet_in.grid_spacing;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_request_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_terrain_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_request_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
mavlink_msg_terrain_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
mavlink_msg_terrain_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_terrain_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_request_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
mavlink_msg_terrain_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_terrain_data(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_terrain_data_t packet_in = {
963497464,
}963497672,
}17651,
}{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764, 17765, 17766, 17767, 17768, 17769, 17770 },
}3,
};
mavlink_terrain_data_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.grid_spacing = packet_in.grid_spacing;
packet1.gridbit = packet_in.gridbit;
mav_array_memcpy(packet1.data, packet_in.data, sizeof(int16_t)*16);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_data_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_terrain_data_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_data_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
mavlink_msg_terrain_data_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
mavlink_msg_terrain_data_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_terrain_data_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_data_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
mavlink_msg_terrain_data_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_terrain_check(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_terrain_check_t packet_in = {
963497464,
}963497672,
};
mavlink_terrain_check_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_check_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_terrain_check_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_check_pack(system_id, component_id, &msg , packet1.lat , packet1.lon );
mavlink_msg_terrain_check_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_check_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon );
mavlink_msg_terrain_check_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_terrain_check_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_check_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon );
mavlink_msg_terrain_check_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_terrain_report(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_terrain_report_t packet_in = {
963497464,
}963497672,
}73.0,
}17859,
}17963,
}18067,
};
mavlink_terrain_report_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.height = packet_in.height;
packet1.spacing = packet_in.spacing;
packet1.pending = packet_in.pending;
packet1.loaded = packet_in.loaded;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_report_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_terrain_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_report_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.height , packet1.pending , packet1.loaded );
mavlink_msg_terrain_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.height , packet1.pending , packet1.loaded );
mavlink_msg_terrain_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_terrain_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_terrain_report_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.spacing , packet1.height , packet1.pending , packet1.loaded );
mavlink_msg_terrain_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -5955,6 +6348,9 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_manual_setpoint(system_id, component_id, last_msg);
mavlink_test_attitude_setpoint_external(system_id, component_id, last_msg);
mavlink_test_local_ned_position_setpoint_external(system_id, component_id, last_msg);
mavlink_test_global_position_setpoint_external_int(system_id, component_id, last_msg);
mavlink_test_local_position_ned_system_global_offset(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg);
@ -5991,6 +6387,10 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_data_transmission_handshake(system_id, component_id, last_msg);
mavlink_test_encapsulated_data(system_id, component_id, last_msg);
mavlink_test_distance_sensor(system_id, component_id, last_msg);
mavlink_test_terrain_request(system_id, component_id, last_msg);
mavlink_test_terrain_data(system_id, component_id, last_msg);
mavlink_test_terrain_check(system_id, component_id, last_msg);
mavlink_test_terrain_report(system_id, component_id, last_msg);
mavlink_test_battery_status(system_id, component_id, last_msg);
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 9 17:11:13 2014"
#define MAVLINK_BUILD_DATE "Thu Jul 24 21:34:30 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -73,7 +73,6 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
#endif
{
// This code part is the same for all messages;
uint16_t checksum;
msg->magic = MAVLINK_STX;
msg->len = length;
msg->sysid = system_id;
@ -81,12 +80,13 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
// One sequence number per component
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
crc_accumulate(crc_extra, &msg->checksum);
#endif
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
@ -133,7 +133,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
buf[4] = mavlink_system.compid;
buf[5] = msgid;
status->current_tx_seq++;
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, packet, length);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
@ -158,6 +158,7 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
// XXX use the right sequence here
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
_mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
@ -172,7 +173,13 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
}

View File

@ -1,7 +1,12 @@
#ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_
// Visual Studio versions before 2013 don't conform to C99.
#if (defined _MSC_VER) & (_MSC_VER < 1800)
#include <stdint.h>
#else
#include <inttypes.h>
#endif
#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
@ -28,6 +33,7 @@
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
#pragma pack(push, 1)
typedef struct param_union {
union {
float param_float;
@ -62,13 +68,12 @@ typedef struct __mavlink_message {
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t;
typedef struct __mavlink_extended_message {
mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;
#pragma pack(pop)
typedef enum {
MAVLINK_TYPE_CHAR = 0,