APMrover2: Changes to fix the warnings in rover sitl build.

We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
This commit is contained in:
Grant Morphett 2015-02-05 17:23:49 +11:00 committed by Andrew Tridgell
parent e7ac9d27f5
commit 4ffb4f6fef
3 changed files with 4 additions and 21 deletions

View File

@ -62,7 +62,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
break; break;
} }
#if ENABLE_STICK_MIXING==ENABLED #if defined(ENABLE_STICK_MIXING) && (ENABLE_STICK_MIXING==ENABLED)
if (control_mode != INITIALISING) { if (control_mode != INITIALISING) {
// all modes except INITIALISING have some form of manual // all modes except INITIALISING have some form of manual
// override if stick mixing is enabled // override if stick mixing is enabled
@ -238,9 +238,9 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
nav_controller->crosstrack_error()); nav_controller->crosstrack_error());
} }
#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 // This is used for HIL. Do not change without discussing with
// HIL maintainers // HIL maintainers
@ -257,8 +257,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
0, 0,
0, 0,
receiver_rssi); receiver_rssi);
}
#endif #endif
}
static void NOINLINE send_radio_out(mavlink_channel_t chan) static void NOINLINE send_radio_out(mavlink_channel_t chan)
{ {
@ -445,10 +445,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

@ -306,7 +306,7 @@ static void Log_Write_Attitude()
DataFlash.Log_Write_Attitude(ahrs, targets); DataFlash.Log_Write_Attitude(ahrs, targets);
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
#if OPTFLOW == ENABLED #if defined(OPTFLOW) and (OPTFLOW == ENABLED)
DataFlash.Log_Write_EKF(ahrs,optflow.enabled()); DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
#else #else
DataFlash.Log_Write_EKF(ahrs,false); DataFlash.Log_Write_EKF(ahrs,false);

View File

@ -481,21 +481,6 @@ static uint8_t check_digital_pin(uint8_t pin)
return hal.gpio->read(dpin); return hal.gpio->read(dpin);
} }
/*
write to a servo
*/
static void servo_write(uint8_t ch, uint16_t pwm)
{
#if HIL_MODE != HIL_MODE_DISABLED
if (ch < 8) {
RC_Channel::rc_channel(ch)->radio_out = pwm;
}
#else
hal.rcout->enable_ch(ch);
hal.rcout->write(ch, pwm);
#endif
}
/* /*
should we log a message type now? should we log a message type now?
*/ */