GCS_MAVLink: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1

This commit is contained in:
Lucas De Marchi 2015-11-03 11:46:30 -02:00 committed by Andrew Tridgell
parent 7cc96f3845
commit 039f42d916
2 changed files with 5 additions and 34 deletions

View File

@ -197,11 +197,8 @@ void GCS_MAVLINK::reset_cli_timeout() {
void GCS_MAVLINK::send_meminfo(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
extern unsigned __brkval;
#else
unsigned __brkval = 0;
#endif
mavlink_msg_meminfo_send(chan, __brkval, hal.util->available_memory());
}
@ -298,7 +295,7 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t
ret_packet.autocontinue = 1; // 1 (true), 0 (false)
/*
avoid the _send() function to save memory on APM2, as it avoids
avoid the _send() function to save memory, as it avoids
the stack usage of the _send() function by using the already
declared ret_packet above
*/
@ -440,9 +437,8 @@ bool GCS_MAVLINK::have_flow_control(void)
/*
handle a request to change stream rate. Note that copter passes in
save==false, as sending mavlink messages on copter on APM2 costs
enough that it can cause flight issues, so we don't want the save to
happen when the user connects the ground station.
save==false so we don't want the save to happen when the user connects the
ground station.
*/
void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
{
@ -510,13 +506,11 @@ void GCS_MAVLINK::handle_param_request_list(mavlink_message_t *msg)
mavlink_param_request_list_t packet;
mavlink_msg_param_request_list_decode(msg, &packet);
#if CONFIG_HAL_BOARD != HAL_BOARD_APM1 && CONFIG_HAL_BOARD != HAL_BOARD_APM2
// send system ID if we can
char sysid[40];
if (hal.util->get_system_id(sysid)) {
send_text(MAV_SEVERITY_WARNING, sysid);
}
#endif
// Start sending parameters - next call to ::update will kick the first one out
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);

View File

@ -20,15 +20,8 @@
// into progmem
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_get_message_crc(msgid)
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
#include <util/crc16.h>
#define HAVE_CRC_ACCUMULATE
// only two telemetry ports on APM1/APM2
#define MAVLINK_COMM_NUM_BUFFERS 2
#else
// allow four telemetry ports on other boards
// allow four telemetry ports
#define MAVLINK_COMM_NUM_BUFFERS 4
#endif
/*
The MAVLink protocol code generator does its own alignment, so
@ -39,14 +32,7 @@
#include "include/mavlink/v1.0/ardupilotmega/version.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
// this allows us to make mavlink_message_t much smaller. It means we
// can't support the largest messages in common.xml, but we don't need
// those for APM1/APM2
#define MAVLINK_MAX_PAYLOAD_LEN 104
#else
#define MAVLINK_MAX_PAYLOAD_LEN 255
#endif
#include "include/mavlink/v1.0/mavlink_types.h"
@ -92,15 +78,6 @@ uint16_t comm_get_available(mavlink_channel_t chan);
/// @returns Number of bytes available
uint16_t comm_get_txspace(mavlink_channel_t chan);
#ifdef HAVE_CRC_ACCUMULATE
// use the AVR C library implementation. This is a bit over twice as
// fast as the C version
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
{
*crcAccum = _crc_ccitt_update(*crcAccum, data);
}
#endif
/*
return true if the MAVLink parser is idle, so there is no partly parsed
MAVLink message being processed