Copter: reduced build warnings

removed some unused code, and mark some functions with UNUSED_FUNCTION
This commit is contained in:
Andrew Tridgell 2015-02-18 11:13:48 +11:00
parent 26ac29840c
commit 307b9e807f
5 changed files with 5 additions and 63 deletions

View File

@ -318,14 +318,13 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
hal.i2c->lockup_count()); hal.i2c->lockup_count());
} }
#if HIL_MODE != HIL_MODE_DISABLED
static void NOINLINE send_servo_out(mavlink_channel_t chan) static void NOINLINE send_servo_out(mavlink_channel_t chan)
{ {
#if HIL_MODE != HIL_MODE_DISABLED
// normalized values scaled to -10000 to 10000 // normalized values scaled to -10000 to 10000
// This is used for HIL. Do not change without discussing with HIL maintainers // This is used for HIL. Do not change without discussing with HIL maintainers
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
mavlink_msg_rc_channels_scaled_send( mavlink_msg_rc_channels_scaled_send(
chan, chan,
millis(), millis(),
@ -340,39 +339,6 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
0, 0,
receiver_rssi); receiver_rssi);
#else #else
#if X_PLANE == ENABLED
/* update by JLN for X-Plane HIL */
if(motors.armed() && ap.auto_armed) {
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
10000 * g.rc_3.norm_output(),
g.rc_4.servo_out,
10000 * g.rc_1.norm_output(),
10000 * g.rc_2.norm_output(),
10000 * g.rc_3.norm_output(),
10000 * g.rc_4.norm_output(),
receiver_rssi);
}else{
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
0,
0,
-10000,
0,
10000 * g.rc_1.norm_output(),
10000 * g.rc_2.norm_output(),
10000 * g.rc_3.norm_output(),
10000 * g.rc_4.norm_output(),
receiver_rssi);
}
#else
mavlink_msg_rc_channels_scaled_send( mavlink_msg_rc_channels_scaled_send(
chan, chan,
millis(), millis(),
@ -386,10 +352,9 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
10000 * g.rc_3.norm_output(), 10000 * g.rc_3.norm_output(),
10000 * g.rc_4.norm_output(), 10000 * g.rc_4.norm_output(),
receiver_rssi); receiver_rssi);
#endif
#endif #endif
}
#endif // HIL_MODE #endif // HIL_MODE
}
static void NOINLINE send_radio_out(mavlink_channel_t chan) static void NOINLINE send_radio_out(mavlink_channel_t chan)
{ {
@ -530,10 +495,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break; break;
case MSG_SERVO_OUT: case MSG_SERVO_OUT:
#if HIL_MODE != HIL_MODE_DISABLED
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED); CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
send_servo_out(chan); send_servo_out(chan);
#endif
break; break;
case MSG_RADIO_IN: case MSG_RADIO_IN:

View File

@ -417,6 +417,7 @@ struct PACKED log_Data_Int16t {
}; };
// Write an int16_t data packet // Write an int16_t data packet
UNUSED_FUNCTION
static void Log_Write_Data(uint8_t id, int16_t value) static void Log_Write_Data(uint8_t id, int16_t value)
{ {
if (should_log(MASK_LOG_ANY)) { if (should_log(MASK_LOG_ANY)) {
@ -436,6 +437,7 @@ struct PACKED log_Data_UInt16t {
}; };
// Write an uint16_t data packet // Write an uint16_t data packet
UNUSED_FUNCTION
static void Log_Write_Data(uint8_t id, uint16_t value) static void Log_Write_Data(uint8_t id, uint16_t value)
{ {
if (should_log(MASK_LOG_ANY)) { if (should_log(MASK_LOG_ANY)) {
@ -493,6 +495,7 @@ struct PACKED log_Data_Float {
}; };
// Write a float data packet // Write a float data packet
UNUSED_FUNCTION
static void Log_Write_Data(uint8_t id, float value) static void Log_Write_Data(uint8_t id, float value)
{ {
if (should_log(MASK_LOG_ANY)) { if (should_log(MASK_LOG_ANY)) {
@ -611,7 +614,6 @@ static void start_logging()
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
static void Log_Write_Startup() {} static void Log_Write_Startup() {}
static void Log_Write_Mode(uint8_t mode) {}
#if AUTOTUNE_ENABLED == ENABLED #if AUTOTUNE_ENABLED == ENABLED
static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp) {} static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp) {}
static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds) {} static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds) {}

View File

@ -5,11 +5,6 @@ static void delay(uint32_t ms)
hal.scheduler->delay(ms); hal.scheduler->delay(ms);
} }
static void mavlink_delay(uint32_t ms)
{
hal.scheduler->delay(ms);
}
static uint32_t millis() static uint32_t millis()
{ {
return hal.scheduler->millis(); return hal.scheduler->millis();

View File

@ -677,23 +677,6 @@ static void autotune_attitude_control()
} }
} }
// autotune has failed, return to standard gains and log event
// called when the autotune is unable to find good gains
static void autotune_failed()
{
// set autotune mode to failed so that it cannot restart
autotune_state.mode = AUTOTUNE_MODE_FAILED;
// set gains to their original values
autotune_load_orig_gains();
// re-enable angle-to-rate request limits
attitude_control.limit_angle_to_rate_request(true);
// log failure
Log_Write_Event(DATA_AUTOTUNE_FAILED);
// play a tone
AP_Notify::events.autotune_failed = 1;
}
// autotune_backup_gains_and_initialise - store current gains as originals // autotune_backup_gains_and_initialise - store current gains as originals
// called before tuning starts to backup original gains // called before tuning starts to backup original gains
static void autotune_backup_gains_and_initialise() static void autotune_backup_gains_and_initialise()

View File

@ -52,7 +52,6 @@ test_mode(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
test_baro(uint8_t argc, const Menu::arg *argv) test_baro(uint8_t argc, const Menu::arg *argv)
{ {
int32_t alt;
print_hit_enter(); print_hit_enter();
init_barometer(true); init_barometer(true);