Copter: To nullptr from NULL.

This commit is contained in:
murata 2016-10-29 01:40:07 +09:00 committed by Tom Pittenger
parent cc8dd92a8c
commit 965a6a5719
3 changed files with 7 additions and 7 deletions

View File

@ -692,7 +692,7 @@ GCS_MAVLINK_Copter::data_stream_send(void)
copter.gcs_out_of_time = false;
if (_queued_parameter != NULL) {
if (_queued_parameter != nullptr) {
if (streamRates[STREAM_PARAMS].get() <= 0) {
streamRates[STREAM_PARAMS].set(10);
}
@ -2060,9 +2060,9 @@ void Copter::gcs_check_input(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(&Copter::run_cli, void, AP_HAL::UARTDriver *):NULL);
gcs[i].update(g.cli_enabled==1?FUNCTOR_BIND_MEMBER(&Copter::run_cli, void, AP_HAL::UARTDriver *):nullptr);
#else
gcs[i].update(NULL);
gcs[i].update(nullptr);
#endif
}
}

View File

@ -176,7 +176,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
set_mask = strtol (argv[1].str, NULL, 2);
set_mask = strtol (argv[1].str, nullptr, 2);
if (set_mask == 0)
cliSerial->printf("no channels chosen");
//cliSerial->printf("\n%d\n",set_mask);

View File

@ -50,7 +50,7 @@ void Copter::run_cli(AP_HAL::UARTDriver *port)
port->set_blocking_writes(true);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
hal.scheduler->register_delay_callback(nullptr, 5);
// disable main_loop failsafe
failsafe_disable();
@ -228,10 +228,10 @@ void Copter::init_ardupilot()
if (g.cli_enabled) {
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);
}
}