mirror of https://github.com/ArduPilot/ardupilot
Tracker: To nullptr from NULL.
This commit is contained in:
parent
629af84ca1
commit
cc8dd92a8c
|
@ -366,7 +366,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|||
void
|
||||
GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||
{
|
||||
if (_queued_parameter != NULL) {
|
||||
if (_queued_parameter != nullptr) {
|
||||
if (streamRates[STREAM_PARAMS].get() <= 0) {
|
||||
streamRates[STREAM_PARAMS].set(10);
|
||||
}
|
||||
|
@ -541,7 +541,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
case MAVLINK_MSG_ID_PARAM_SET:
|
||||
{
|
||||
handle_param_set(msg, NULL);
|
||||
handle_param_set(msg, nullptr);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -940,7 +940,7 @@ void Tracker::gcs_update(void)
|
|||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].update(NULL);
|
||||
gcs[i].update(nullptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -42,7 +42,7 @@ void Tracker::update_compass(void)
|
|||
DataFlash.Log_Write_Compass(compass);
|
||||
}
|
||||
} else {
|
||||
ahrs.set_compass(NULL);
|
||||
ahrs.set_compass(nullptr);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@ void Tracker::init_tracker()
|
|||
}
|
||||
|
||||
// GPS Initialization
|
||||
gps.init(NULL, serial_manager);
|
||||
gps.init(nullptr, serial_manager);
|
||||
|
||||
ahrs.init();
|
||||
ahrs.set_fly_forward(false);
|
||||
|
|
Loading…
Reference in New Issue