mirror of https://github.com/ArduPilot/ardupilot
Rover: fixed build warnings
This commit is contained in:
parent
cd8b001f63
commit
a575608110
|
@ -640,7 +640,7 @@ void Rover::load_parameters(void)
|
|||
Parameters::k_param_rc_13_old, Parameters::k_param_rc_14_old };
|
||||
const uint16_t old_aux_chan_mask = 0x3FFA;
|
||||
SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, &rcmap);
|
||||
hal.console->printf("load_all took %uus\n", micros() - before);
|
||||
hal.console->printf("load_all took %uus\n", unsigned(micros() - before));
|
||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||
L1_controller.set_default_period(NAVL1_PERIOD);
|
||||
}
|
||||
|
|
|
@ -178,7 +178,7 @@ void Rover::read_aux_switch()
|
|||
|
||||
// save command
|
||||
if (mission.add_cmd(cmd)) {
|
||||
hal.console->printf("Added waypoint %u", static_cast<uint32_t>(mission.num_commands()));
|
||||
hal.console->printf("Added waypoint %u", unsigned(mission.num_commands()));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -25,7 +25,7 @@ void Rover::init_ardupilot()
|
|||
hal.console->printf("\n\nInit %s"
|
||||
"\n\nFree RAM: %u\n",
|
||||
fwver.fw_string,
|
||||
hal.util->available_memory());
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
//
|
||||
// Check the EEPROM format version before loading any parameters from EEPROM.
|
||||
|
|
Loading…
Reference in New Issue