Rover: To nullptr from NULL.

This commit is contained in:
murata 2016-10-29 01:57:14 +09:00 committed by Lucas De Marchi
parent 965a6a5719
commit a71e889f51
4 changed files with 11 additions and 11 deletions

View File

@ -233,7 +233,7 @@ void Rover::update_compass(void)
DataFlash.Log_Write_Compass(compass);
}
} else {
ahrs.set_compass(NULL);
ahrs.set_compass(nullptr);
}
}

View File

@ -586,7 +586,7 @@ GCS_MAVLINK_Rover::data_stream_send(void)
handle_log_send(rover.DataFlash);
}
if (_queued_parameter != NULL) {
if (_queued_parameter != nullptr) {
if (streamRates[STREAM_PARAMS].get() <= 0) {
streamRates[STREAM_PARAMS].set(10);
}
@ -1526,9 +1526,9 @@ void Rover::gcs_update(void)
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
#if CLI_ENABLED == ENABLED
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : NULL);
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : nullptr);
#else
gcs[i].update(NULL);
gcs[i].update(nullptr);
#endif
}
}

View File

@ -21,9 +21,9 @@
Rover::Rover(void) :
param_loader(var_info),
channel_steer(NULL),
channel_throttle(NULL),
channel_learn(NULL),
channel_steer(nullptr),
channel_throttle(nullptr),
channel_learn(nullptr),
DataFlash{FIRMWARE_STRING},
in_log_download(false),
modes(&g.mode1),

View File

@ -48,10 +48,10 @@ int8_t Rover::reboot_board(uint8_t argc, const Menu::arg *argv)
void Rover::run_cli(AP_HAL::UARTDriver *port)
{
// disable the failsafe code in the CLI
hal.scheduler->register_timer_failsafe(NULL,1);
hal.scheduler->register_timer_failsafe(nullptr,1);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
hal.scheduler->register_delay_callback(nullptr, 5);
cliSerial = port;
Menu::set_port(port);
@ -185,10 +185,10 @@ void Rover::init_ardupilot()
if (g.cli_enabled == 1) {
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
cliSerial->println(msg);
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) {
gcs[1].get_uart()->println(msg);
}
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != nullptr)) {
gcs[2].get_uart()->println(msg);
}
}