Copter: reduce compiler warnings
This commit is contained in:
parent
e58f49aeaf
commit
1dcd46bffc
@ -271,13 +271,13 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
|||||||
ahrs.get_error_yaw());
|
ahrs.get_error_yaw());
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
|
||||||
// report simulator state
|
// report simulator state
|
||||||
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||||
sitl.simstate_send(chan);
|
sitl.simstate_send(chan);
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
@ -1089,10 +1089,10 @@ struct log_DMP {
|
|||||||
uint16_t dmp_yaw;
|
uint16_t dmp_yaw;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if SECONDARY_DMP_ENABLED == ENABLED
|
||||||
// Write a DMP attitude packet. Total length : 16 bytes
|
// Write a DMP attitude packet. Total length : 16 bytes
|
||||||
static void Log_Write_DMP()
|
static void Log_Write_DMP()
|
||||||
{
|
{
|
||||||
#if SECONDARY_DMP_ENABLED == ENABLED
|
|
||||||
struct log_DMP pkt = {
|
struct log_DMP pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_DMP_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_DMP_MSG),
|
||||||
dcm_roll : (int16_t)ahrs.roll_sensor,
|
dcm_roll : (int16_t)ahrs.roll_sensor,
|
||||||
@ -1103,8 +1103,8 @@ static void Log_Write_DMP()
|
|||||||
dmp_yaw : (uint16_t)ahrs2.yaw_sensor
|
dmp_yaw : (uint16_t)ahrs2.yaw_sensor
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Read a DMP attitude packet
|
// Read a DMP attitude packet
|
||||||
static void Log_Read_DMP()
|
static void Log_Read_DMP()
|
||||||
@ -1374,7 +1374,9 @@ static void Log_Write_Control_Tuning() {}
|
|||||||
static void Log_Write_Motors() {}
|
static void Log_Write_Motors() {}
|
||||||
static void Log_Write_Performance() {}
|
static void Log_Write_Performance() {}
|
||||||
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {}
|
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {}
|
||||||
|
#if SECONDARY_DMP_ENABLED == ENABLED
|
||||||
static void Log_Write_DMP() {}
|
static void Log_Write_DMP() {}
|
||||||
|
#endif
|
||||||
static void Log_Write_Camera() {}
|
static void Log_Write_Camera() {}
|
||||||
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
||||||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
|
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
|
||||||
|
@ -3,9 +3,6 @@
|
|||||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
// Sensors are not available in HIL_MODE_ATTITUDE
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
static void ReadSCP1000(void) {
|
|
||||||
}
|
|
||||||
|
|
||||||
#if CONFIG_SONAR == ENABLED
|
#if CONFIG_SONAR == ENABLED
|
||||||
static void init_sonar(void)
|
static void init_sonar(void)
|
||||||
{
|
{
|
||||||
|
@ -301,31 +301,6 @@ setup_accel(uint8_t argc, const Menu::arg *argv)
|
|||||||
return(0);
|
return(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
handle full accelerometer calibration via user dialog
|
|
||||||
*/
|
|
||||||
|
|
||||||
static void setup_printf_P(const prog_char_t *fmt, ...)
|
|
||||||
{
|
|
||||||
va_list arg_list;
|
|
||||||
va_start(arg_list, fmt);
|
|
||||||
cliSerial->printf_P(fmt, arg_list);
|
|
||||||
va_end(arg_list);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void setup_wait_key(void)
|
|
||||||
{
|
|
||||||
// wait for user input
|
|
||||||
while (!cliSerial->available()) {
|
|
||||||
delay(20);
|
|
||||||
}
|
|
||||||
// clear input buffer
|
|
||||||
while( cliSerial->available() ) {
|
|
||||||
cliSerial->read();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static int8_t
|
static int8_t
|
||||||
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
@ -33,7 +33,7 @@ static int8_t test_optflow(uint8_t argc, const Menu::arg *argv);
|
|||||||
static int8_t test_logging(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_logging(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_mission(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_mission(uint8_t argc, const Menu::arg *argv);
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||||
@ -1088,10 +1088,12 @@ static void print_hit_enter()
|
|||||||
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
|
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined( __AVR_ATmega1280__ )
|
||||||
static void print_test_disabled()
|
static void print_test_disabled()
|
||||||
{
|
{
|
||||||
cliSerial->printf_P(PSTR("Sorry, not 1280 compat.\n"));
|
cliSerial->printf_P(PSTR("Sorry, not 1280 compat.\n"));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* //static void fake_out_gps()
|
* //static void fake_out_gps()
|
||||||
|
Loading…
Reference in New Issue
Block a user