Global: To nullptr from NULL.
RC_Channel: To nullptr from NULL. AC_Fence: To nullptr from NULL. AC_Avoidance: To nullptr from NULL. AC_PrecLand: To nullptr from NULL. DataFlash: To nullptr from NULL. SITL: To nullptr from NULL. GCS_MAVLink: To nullptr from NULL. DataFlash: To nullptr from NULL. AP_Compass: To nullptr from NULL. Global: To nullptr from NULL. Global: To nullptr from NULL.
This commit is contained in:
parent
5386edb791
commit
c808ee2f49
@ -115,7 +115,7 @@ void AC_Avoid::adjust_velocity_poly(const float kP, const float accel_cmss, Vect
|
||||
Vector2f* boundary = _fence.get_polygon_points(num_points);
|
||||
|
||||
// exit if there are no points
|
||||
if (boundary == NULL || num_points == 0) {
|
||||
if (boundary == nullptr || num_points == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -345,7 +345,7 @@ bool AC_Fence::boundary_breached(const Vector2f& location, uint16_t num_points,
|
||||
void AC_Fence::handle_msg(mavlink_channel_t chan, mavlink_message_t* msg)
|
||||
{
|
||||
// exit immediately if null message
|
||||
if (msg == NULL) {
|
||||
if (msg == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -405,7 +405,7 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
|
||||
}
|
||||
|
||||
// exit if we could not allocate RAM for the boundary
|
||||
if (_boundary == NULL) {
|
||||
if (_boundary == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -156,7 +156,7 @@ private:
|
||||
|
||||
// polygon fence variables
|
||||
AC_PolyFence_loader _poly_loader; // helper for loading/saving polygon points
|
||||
Vector2f *_boundary = NULL; // array of boundary points. Note: point 0 is the return point
|
||||
Vector2f *_boundary = nullptr; // array of boundary points. Note: point 0 is the return point
|
||||
uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed)
|
||||
bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array
|
||||
bool _boundary_loaded = false; // true if boundary array has been loaded from eeprom
|
||||
|
@ -13,13 +13,13 @@ uint8_t AC_PolyFence_loader::max_points() const
|
||||
}
|
||||
|
||||
// create buffer to hold copy of eeprom points in RAM
|
||||
// returns NULL if not enough memory can be allocated
|
||||
// returns nullptr if not enough memory can be allocated
|
||||
void* AC_PolyFence_loader::create_point_array(uint8_t element_size)
|
||||
{
|
||||
uint32_t array_size = max_points() * element_size;
|
||||
if (hal.util->available_memory() < 100U + array_size) {
|
||||
// too risky to enable as we could run out of stack
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return calloc(1, array_size);
|
||||
@ -59,7 +59,7 @@ bool AC_PolyFence_loader::save_point_to_eeprom(uint16_t i, const Vector2l& point
|
||||
bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2l* points, bool contains_return_point) const
|
||||
{
|
||||
// exit immediate if no points
|
||||
if (points == NULL) {
|
||||
if (points == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -87,7 +87,7 @@ bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2l* po
|
||||
bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2f* points, bool contains_return_point) const
|
||||
{
|
||||
// exit immediate if no points
|
||||
if (points == NULL) {
|
||||
if (points == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -118,7 +118,7 @@ bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2f* po
|
||||
bool AC_PolyFence_loader::boundary_breached(const Vector2l& location, uint16_t num_points, const Vector2l* points, bool contains_return_point) const
|
||||
{
|
||||
// exit immediate if no points
|
||||
if (points == NULL) {
|
||||
if (points == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -132,7 +132,7 @@ bool AC_PolyFence_loader::boundary_breached(const Vector2l& location, uint16_t n
|
||||
bool AC_PolyFence_loader::boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points, bool contains_return_point) const
|
||||
{
|
||||
// exit immediate if no points
|
||||
if (points == NULL) {
|
||||
if (points == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -12,7 +12,7 @@ public:
|
||||
uint8_t max_points() const;
|
||||
|
||||
// create buffer to hold copy of eeprom points in RAM
|
||||
// returns NULL if not enough memory can be allocated
|
||||
// returns nullptr if not enough memory can be allocated
|
||||
void* create_point_array(uint8_t element_size);
|
||||
|
||||
// load boundary point from eeprom, returns true on successful load
|
||||
|
@ -60,7 +60,7 @@ AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) :
|
||||
_inav(inav),
|
||||
_last_update_ms(0),
|
||||
_last_backend_los_meas_ms(0),
|
||||
_backend(NULL)
|
||||
_backend(nullptr)
|
||||
{
|
||||
// set parameters to defaults
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
@ -74,12 +74,12 @@ AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) :
|
||||
void AC_PrecLand::init()
|
||||
{
|
||||
// exit immediately if init has already been run
|
||||
if (_backend != NULL) {
|
||||
if (_backend != nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
// default health to false
|
||||
_backend = NULL;
|
||||
_backend = nullptr;
|
||||
_backend_state.healthy = false;
|
||||
|
||||
// instantiate backend based on type parameter
|
||||
@ -101,7 +101,7 @@ void AC_PrecLand::init()
|
||||
}
|
||||
|
||||
// init backend
|
||||
if (_backend != NULL) {
|
||||
if (_backend != nullptr) {
|
||||
_backend->init();
|
||||
}
|
||||
}
|
||||
@ -112,7 +112,7 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
|
||||
_attitude_history.push_back(_ahrs.get_rotation_body_to_ned());
|
||||
|
||||
// run backend update
|
||||
if (_backend != NULL && _enabled) {
|
||||
if (_backend != nullptr && _enabled) {
|
||||
// read from sensor
|
||||
_backend->update();
|
||||
|
||||
@ -228,7 +228,7 @@ bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret) const
|
||||
void AC_PrecLand::handle_msg(mavlink_message_t* msg)
|
||||
{
|
||||
// run backend update
|
||||
if (_backend != NULL) {
|
||||
if (_backend != nullptr) {
|
||||
_backend->handle_msg(msg);
|
||||
}
|
||||
}
|
||||
|
@ -303,7 +303,7 @@ void AC_WPNav::calc_loiter_desired_velocity(float nav_dt, float ekfGndSpdLimit)
|
||||
}
|
||||
|
||||
// Limit the velocity to prevent fence violations
|
||||
if (_avoid != NULL) {
|
||||
if (_avoid != nullptr) {
|
||||
_avoid->adjust_velocity(_pos_control.get_pos_xy_kP(), _loiter_accel_cmss, desired_vel);
|
||||
}
|
||||
|
||||
@ -1170,7 +1170,7 @@ bool AC_WPNav::get_terrain_offset(float& offset_cm)
|
||||
|
||||
// use terrain database
|
||||
float terr_alt = 0.0f;
|
||||
if (_terrain != NULL && _terrain->height_above_terrain(terr_alt, true)) {
|
||||
if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) {
|
||||
offset_cm = _inav.get_altitude() - (terr_alt * 100.0f);
|
||||
return true;
|
||||
}
|
||||
|
@ -313,8 +313,8 @@ protected:
|
||||
const AP_AHRS& _ahrs;
|
||||
AC_PosControl& _pos_control;
|
||||
const AC_AttitudeControl& _attitude_control;
|
||||
AP_Terrain *_terrain = NULL;
|
||||
AC_Avoid *_avoid = NULL;
|
||||
AP_Terrain *_terrain = nullptr;
|
||||
AC_Avoid *_avoid = nullptr;
|
||||
|
||||
// parameters
|
||||
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter
|
||||
|
@ -54,9 +54,9 @@ public:
|
||||
pitch_sensor(0),
|
||||
yaw_sensor(0),
|
||||
_vehicle_class(AHRS_VEHICLE_UNKNOWN),
|
||||
_compass(NULL),
|
||||
_optflow(NULL),
|
||||
_airspeed(NULL),
|
||||
_compass(nullptr),
|
||||
_optflow(nullptr),
|
||||
_airspeed(nullptr),
|
||||
_compass_last_update(0),
|
||||
_ins(ins),
|
||||
_baro(baro),
|
||||
@ -140,7 +140,7 @@ public:
|
||||
// this makes initial config easier
|
||||
void set_orientation() {
|
||||
_ins.set_board_orientation((enum Rotation)_board_orientation.get());
|
||||
if (_compass != NULL) {
|
||||
if (_compass != nullptr) {
|
||||
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
|
||||
}
|
||||
}
|
||||
@ -278,7 +278,7 @@ public:
|
||||
// return true if airspeed comes from an airspeed sensor, as
|
||||
// opposed to an IMU estimate
|
||||
bool airspeed_sensor_enabled(void) const {
|
||||
return _airspeed != NULL && _airspeed->use() && _airspeed->healthy();
|
||||
return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
|
||||
}
|
||||
|
||||
// return a ground vector estimate in meters/second, in North/East order
|
||||
|
@ -40,7 +40,7 @@ void setup(void)
|
||||
} else {
|
||||
hal.console->printf("No compass detected\n");
|
||||
}
|
||||
gps.init(NULL, serial_manager);
|
||||
gps.init(nullptr, serial_manager);
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
|
@ -45,7 +45,7 @@ void AP_AccelCal::update()
|
||||
}
|
||||
if(_start_collect_sample) {
|
||||
collect_sample();
|
||||
_gcs->set_snoop(NULL);
|
||||
_gcs->set_snoop(nullptr);
|
||||
_start_collect_sample = false;
|
||||
}
|
||||
switch(_status) {
|
||||
@ -55,7 +55,7 @@ void AP_AccelCal::update()
|
||||
case ACCEL_CAL_WAITING_FOR_ORIENTATION: {
|
||||
// if we're waiting for orientation, first ensure that all calibrators are on the same step
|
||||
uint8_t step;
|
||||
if ((cal = get_calibrator(0)) == NULL) {
|
||||
if ((cal = get_calibrator(0)) == nullptr) {
|
||||
fail();
|
||||
return;
|
||||
}
|
||||
@ -153,7 +153,7 @@ void AP_AccelCal::update()
|
||||
|
||||
void AP_AccelCal::start(GCS_MAVLINK *gcs)
|
||||
{
|
||||
if (gcs == NULL || _started) {
|
||||
if (gcs == nullptr || _started) {
|
||||
return;
|
||||
}
|
||||
_start_collect_sample = false;
|
||||
@ -218,7 +218,7 @@ void AP_AccelCal::clear()
|
||||
cal->clear();
|
||||
}
|
||||
|
||||
_gcs = NULL;
|
||||
_gcs = nullptr;
|
||||
|
||||
_step = 0;
|
||||
_started = false;
|
||||
@ -245,12 +245,12 @@ void AP_AccelCal::collect_sample()
|
||||
cal->collect_sample();
|
||||
}
|
||||
// setup snooping of packets so we can see the COMMAND_ACK
|
||||
_gcs->set_snoop(NULL);
|
||||
_gcs->set_snoop(nullptr);
|
||||
update_status();
|
||||
}
|
||||
|
||||
void AP_AccelCal::register_client(AP_AccelCal_Client* client) {
|
||||
if (client == NULL || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {
|
||||
if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -274,7 +274,7 @@ AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) {
|
||||
index--;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void AP_AccelCal::update_status() {
|
||||
|
@ -29,7 +29,7 @@ const extern AP_HAL::HAL& hal;
|
||||
|
||||
AccelCalibrator::AccelCalibrator() :
|
||||
_conf_tolerance(ACCEL_CAL_TOLERANCE),
|
||||
_sample_buffer(NULL)
|
||||
_sample_buffer(nullptr)
|
||||
{
|
||||
clear();
|
||||
}
|
||||
@ -239,7 +239,7 @@ void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f
|
||||
*/
|
||||
bool AccelCalibrator::accept_sample(const Vector3f& sample)
|
||||
{
|
||||
if (_sample_buffer == NULL) {
|
||||
if (_sample_buffer == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -262,9 +262,9 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) {
|
||||
_status = ACCEL_CAL_NOT_STARTED;
|
||||
|
||||
_samples_collected = 0;
|
||||
if (_sample_buffer != NULL) {
|
||||
if (_sample_buffer != nullptr) {
|
||||
free(_sample_buffer);
|
||||
_sample_buffer = NULL;
|
||||
_sample_buffer = nullptr;
|
||||
}
|
||||
|
||||
break;
|
||||
@ -273,9 +273,9 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) {
|
||||
//Callibrator has been started and is waiting for user to ack after orientation setting
|
||||
if (!running()) {
|
||||
_samples_collected = 0;
|
||||
if (_sample_buffer == NULL) {
|
||||
if (_sample_buffer == nullptr) {
|
||||
_sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample));
|
||||
if (_sample_buffer == NULL) {
|
||||
if (_sample_buffer == nullptr) {
|
||||
set_status(ACCEL_CAL_FAILED);
|
||||
break;
|
||||
}
|
||||
@ -325,7 +325,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) {
|
||||
*/
|
||||
void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)
|
||||
{
|
||||
if (_sample_buffer == NULL) {
|
||||
if (_sample_buffer == nullptr) {
|
||||
return;
|
||||
}
|
||||
fitness = calc_mean_squared_residuals(_param.s);
|
||||
@ -407,7 +407,7 @@ float AccelCalibrator::calc_mean_squared_residuals() const
|
||||
// supplied
|
||||
float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const
|
||||
{
|
||||
if (_sample_buffer == NULL || _samples_collected == 0) {
|
||||
if (_sample_buffer == nullptr || _samples_collected == 0) {
|
||||
return 1.0e30f;
|
||||
}
|
||||
float sum = 0.0f;
|
||||
|
@ -37,7 +37,7 @@ bool AP_Airspeed_Analog::init()
|
||||
// read the airspeed sensor
|
||||
bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
|
||||
{
|
||||
if (_source == NULL) {
|
||||
if (_source == nullptr) {
|
||||
return false;
|
||||
}
|
||||
_source->set_pin(_pin);
|
||||
|
@ -9,7 +9,7 @@ class AP_Airspeed_Analog : public AP_Airspeed_Backend
|
||||
{
|
||||
public:
|
||||
AP_Airspeed_Analog(const AP_Int8 &pin, const AP_Float &psi_range)
|
||||
: _source(NULL)
|
||||
: _source(nullptr)
|
||||
, _pin(pin)
|
||||
, _psi_range(psi_range)
|
||||
{ }
|
||||
|
@ -125,7 +125,7 @@ bool AP_Arming::airspeed_checks(bool report)
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_AIRSPEED)) {
|
||||
const AP_Airspeed *airspeed = ahrs.get_airspeed();
|
||||
if (airspeed == NULL) {
|
||||
if (airspeed == nullptr) {
|
||||
// not an airspeed capable vehicle
|
||||
return true;
|
||||
}
|
||||
|
@ -125,10 +125,10 @@ AP_Avoidance::AP_Avoidance(AP_AHRS &ahrs, AP_ADSB &adsb) :
|
||||
void AP_Avoidance::init(void)
|
||||
{
|
||||
debug("ADSB initialisation: %d obstacles", _obstacles_max.get());
|
||||
if (_obstacles == NULL) {
|
||||
if (_obstacles == nullptr) {
|
||||
_obstacles = new AP_Avoidance::Obstacle[_obstacles_max];
|
||||
|
||||
if (_obstacles == NULL) {
|
||||
if (_obstacles == nullptr) {
|
||||
// dynamic RAM allocation of _obstacles[] failed, disable gracefully
|
||||
hal.console->printf("Unable to initialize Avoidance obstacle list\n");
|
||||
// disable ourselves to avoid repeated allocation attempts
|
||||
|
@ -324,7 +324,7 @@ void AP_Baro::init(void)
|
||||
_num_drivers = 1;
|
||||
#endif
|
||||
|
||||
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == NULL) {
|
||||
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
|
||||
AP_HAL::panic("Baro: unable to initialise driver");
|
||||
}
|
||||
}
|
||||
|
@ -190,7 +190,7 @@ AP_BattMonitor::init()
|
||||
}
|
||||
|
||||
// call init function for each backend
|
||||
if (drivers[instance] != NULL) {
|
||||
if (drivers[instance] != nullptr) {
|
||||
drivers[instance]->init();
|
||||
}
|
||||
}
|
||||
@ -201,7 +201,7 @@ void
|
||||
AP_BattMonitor::read()
|
||||
{
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
if (drivers[i] != NULL && _monitoring[i] != BattMonitor_TYPE_NONE) {
|
||||
if (drivers[i] != nullptr && _monitoring[i] != BattMonitor_TYPE_NONE) {
|
||||
drivers[i]->read();
|
||||
}
|
||||
}
|
||||
@ -220,7 +220,7 @@ bool AP_BattMonitor::is_powering_off(uint8_t instance) const {
|
||||
bool AP_BattMonitor::has_current(uint8_t instance) const
|
||||
{
|
||||
// check for analog voltage and current monitor or smbus monitor
|
||||
if (instance < _num_instances && drivers[instance] != NULL) {
|
||||
if (instance < _num_instances && drivers[instance] != nullptr) {
|
||||
return (_monitoring[instance] == BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT ||
|
||||
_monitoring[instance] == BattMonitor_TYPE_SMBUS ||
|
||||
_monitoring[instance] == BattMonitor_TYPE_BEBOP);
|
||||
@ -261,7 +261,7 @@ float AP_BattMonitor::current_total_mah(uint8_t instance) const {
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
|
||||
{
|
||||
if (instance < _num_instances && drivers[instance] != NULL) {
|
||||
if (instance < _num_instances && drivers[instance] != nullptr) {
|
||||
return drivers[instance]->capacity_remaining_pct();
|
||||
} else {
|
||||
return 0;
|
||||
|
@ -122,7 +122,7 @@ void AP_BoardConfig::px4_setup_uart()
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser1_rtscts.get());
|
||||
if (hal.uartD != NULL) {
|
||||
if (hal.uartD != nullptr) {
|
||||
hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser2_rtscts.get());
|
||||
}
|
||||
#endif
|
||||
|
@ -10,8 +10,8 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_AHRS_NavEKF *Location_Class::_ahrs = NULL;
|
||||
AP_Terrain *Location_Class::_terrain = NULL;
|
||||
const AP_AHRS_NavEKF *Location_Class::_ahrs = nullptr;
|
||||
AP_Terrain *Location_Class::_terrain = nullptr;
|
||||
|
||||
// scalers to convert latitude and longitude to meters. Duplicated from location.cpp
|
||||
#define LOCATION_SCALING_FACTOR 0.011131884502145034f
|
||||
@ -45,7 +45,7 @@ Location_Class::Location_Class(const Vector3f &ekf_offset_neu)
|
||||
set_alt_cm(ekf_offset_neu.z, ALT_FRAME_ABOVE_ORIGIN);
|
||||
|
||||
// calculate lat, lon
|
||||
if (_ahrs != NULL) {
|
||||
if (_ahrs != nullptr) {
|
||||
Location ekf_origin;
|
||||
if (_ahrs->get_origin(ekf_origin)) {
|
||||
lat = ekf_origin.lat;
|
||||
@ -130,7 +130,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co
|
||||
float alt_terr_cm = 0;
|
||||
if (frame == ALT_FRAME_ABOVE_TERRAIN || desired_frame == ALT_FRAME_ABOVE_TERRAIN) {
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
if (_ahrs == NULL || _terrain == NULL || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) {
|
||||
if (_ahrs == nullptr || _terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) {
|
||||
return false;
|
||||
}
|
||||
// convert terrain alt to cm
|
||||
@ -153,7 +153,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co
|
||||
{
|
||||
// fail if we cannot get ekf origin
|
||||
Location ekf_origin;
|
||||
if (_ahrs == NULL || !_ahrs->get_origin(ekf_origin)) {
|
||||
if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) {
|
||||
return false;
|
||||
}
|
||||
alt_abs = alt + ekf_origin.alt;
|
||||
@ -179,7 +179,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co
|
||||
{
|
||||
// fail if we cannot get ekf origin
|
||||
Location ekf_origin;
|
||||
if (_ahrs == NULL || !_ahrs->get_origin(ekf_origin)) {
|
||||
if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) {
|
||||
return false;
|
||||
}
|
||||
ret_alt_cm = alt_abs - ekf_origin.alt;
|
||||
|
@ -420,7 +420,7 @@ Compass::Compass(void) :
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
|
||||
_backends[i] = NULL;
|
||||
_backends[i] = nullptr;
|
||||
_state[i].last_update_usec = 0;
|
||||
}
|
||||
|
||||
|
@ -36,12 +36,12 @@ AP_Compass_HIL::AP_Compass_HIL(Compass &compass):
|
||||
AP_Compass_Backend *AP_Compass_HIL::detect(Compass &compass)
|
||||
{
|
||||
AP_Compass_HIL *sensor = new AP_Compass_HIL(compass);
|
||||
if (sensor == NULL) {
|
||||
return NULL;
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return sensor;
|
||||
}
|
||||
|
@ -51,12 +51,12 @@ AP_Compass_PX4::AP_Compass_PX4(Compass &compass):
|
||||
AP_Compass_Backend *AP_Compass_PX4::detect(Compass &compass)
|
||||
{
|
||||
AP_Compass_PX4 *sensor = new AP_Compass_PX4(compass);
|
||||
if (sensor == NULL) {
|
||||
return NULL;
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return sensor;
|
||||
}
|
||||
|
@ -34,12 +34,12 @@ AP_Compass_QURT::AP_Compass_QURT(Compass &compass):
|
||||
AP_Compass_Backend *AP_Compass_QURT::detect(Compass &compass)
|
||||
{
|
||||
AP_Compass_QURT *sensor = new AP_Compass_QURT(compass);
|
||||
if (sensor == NULL) {
|
||||
return NULL;
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return sensor;
|
||||
}
|
||||
|
@ -34,12 +34,12 @@ AP_Compass_QFLIGHT::AP_Compass_QFLIGHT(Compass &compass):
|
||||
AP_Compass_Backend *AP_Compass_QFLIGHT::detect(Compass &compass)
|
||||
{
|
||||
AP_Compass_QFLIGHT *sensor = new AP_Compass_QFLIGHT(compass);
|
||||
if (sensor == NULL) {
|
||||
return NULL;
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return sensor;
|
||||
}
|
||||
|
@ -77,7 +77,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
CompassCalibrator::CompassCalibrator():
|
||||
_tolerance(COMPASS_CAL_DEFAULT_TOLERANCE),
|
||||
_sample_buffer(NULL)
|
||||
_sample_buffer(nullptr)
|
||||
{
|
||||
clear();
|
||||
}
|
||||
@ -263,9 +263,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
|
||||
reset_state();
|
||||
_status = COMPASS_CAL_NOT_STARTED;
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
if(_sample_buffer != nullptr) {
|
||||
free(_sample_buffer);
|
||||
_sample_buffer = NULL;
|
||||
_sample_buffer = nullptr;
|
||||
}
|
||||
return true;
|
||||
|
||||
@ -285,13 +285,13 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (_sample_buffer == NULL) {
|
||||
if (_sample_buffer == nullptr) {
|
||||
_sample_buffer =
|
||||
(CompassSample*) malloc(sizeof(CompassSample) *
|
||||
COMPASS_CAL_NUM_SAMPLES);
|
||||
}
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
if(_sample_buffer != nullptr) {
|
||||
initialize_fit();
|
||||
_status = COMPASS_CAL_RUNNING_STEP_ONE;
|
||||
return true;
|
||||
@ -313,9 +313,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
if(_sample_buffer != nullptr) {
|
||||
free(_sample_buffer);
|
||||
_sample_buffer = NULL;
|
||||
_sample_buffer = nullptr;
|
||||
}
|
||||
|
||||
_status = COMPASS_CAL_SUCCESS;
|
||||
@ -331,9 +331,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if(_sample_buffer != NULL) {
|
||||
if(_sample_buffer != nullptr) {
|
||||
free(_sample_buffer);
|
||||
_sample_buffer = NULL;
|
||||
_sample_buffer = nullptr;
|
||||
}
|
||||
|
||||
_status = COMPASS_CAL_FAILED;
|
||||
@ -363,7 +363,7 @@ bool CompassCalibrator::fit_acceptable() {
|
||||
}
|
||||
|
||||
void CompassCalibrator::thin_samples() {
|
||||
if(_sample_buffer == NULL) {
|
||||
if(_sample_buffer == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -410,7 +410,7 @@ bool CompassCalibrator::accept_sample(const Vector3f& sample)
|
||||
static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
|
||||
static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
|
||||
|
||||
if(_sample_buffer == NULL) {
|
||||
if(_sample_buffer == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -445,7 +445,7 @@ float CompassCalibrator::calc_mean_squared_residuals() const
|
||||
|
||||
float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const
|
||||
{
|
||||
if(_sample_buffer == NULL || _samples_collected == 0) {
|
||||
if(_sample_buffer == nullptr || _samples_collected == 0) {
|
||||
return 1.0e30f;
|
||||
}
|
||||
float sum = 0.0f;
|
||||
@ -493,7 +493,7 @@ void CompassCalibrator::calc_initial_offset()
|
||||
|
||||
void CompassCalibrator::run_sphere_fit()
|
||||
{
|
||||
if(_sample_buffer == NULL) {
|
||||
if(_sample_buffer == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -607,7 +607,7 @@ void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param
|
||||
|
||||
void CompassCalibrator::run_ellipsoid_fit()
|
||||
{
|
||||
if(_sample_buffer == NULL) {
|
||||
if(_sample_buffer == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -57,7 +57,7 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
|
||||
}
|
||||
}
|
||||
|
||||
if (_port != NULL) {
|
||||
if (_port != nullptr) {
|
||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::tick, void));
|
||||
// we don't want flow control for either protocol
|
||||
_port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
|
@ -235,7 +235,7 @@ void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
|
||||
void AP_GPS::send_blob_update(uint8_t instance)
|
||||
{
|
||||
// exit immediately if no uart for this instance
|
||||
if (_port[instance] == NULL) {
|
||||
if (_port[instance] == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -262,7 +262,7 @@ void AP_GPS::send_blob_update(uint8_t instance)
|
||||
void
|
||||
AP_GPS::detect_instance(uint8_t instance)
|
||||
{
|
||||
AP_GPS_Backend *new_gps = NULL;
|
||||
AP_GPS_Backend *new_gps = nullptr;
|
||||
struct detect_state *dstate = &detect_state[instance];
|
||||
uint32_t now = AP_HAL::millis();
|
||||
|
||||
@ -288,11 +288,11 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
// do not try to detect the MAV type, assume it's there
|
||||
if (_type[instance] == GPS_TYPE_MAV) {
|
||||
_broadcast_gps_type("MAV", instance, -1);
|
||||
new_gps = new AP_GPS_MAV(*this, state[instance], NULL);
|
||||
new_gps = new AP_GPS_MAV(*this, state[instance], nullptr);
|
||||
goto found_gps;
|
||||
}
|
||||
|
||||
if (_port[instance] == NULL) {
|
||||
if (_port[instance] == nullptr) {
|
||||
// UART not available
|
||||
return;
|
||||
}
|
||||
@ -342,7 +342,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
}
|
||||
|
||||
while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
|
||||
&& new_gps == NULL) {
|
||||
&& new_gps == nullptr) {
|
||||
uint8_t data = _port[instance]->read();
|
||||
/*
|
||||
running a uBlox at less than 38400 will lead to packet
|
||||
@ -395,7 +395,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
}
|
||||
|
||||
found_gps:
|
||||
if (new_gps != NULL) {
|
||||
if (new_gps != nullptr) {
|
||||
state[instance].status = NO_FIX;
|
||||
drivers[instance] = new_gps;
|
||||
timing[instance].last_message_time_ms = now;
|
||||
@ -405,7 +405,7 @@ found_gps:
|
||||
AP_GPS::GPS_Status
|
||||
AP_GPS::highest_supported_status(uint8_t instance) const
|
||||
{
|
||||
if (drivers[instance] != NULL)
|
||||
if (drivers[instance] != nullptr)
|
||||
return drivers[instance]->highest_supported_status();
|
||||
return AP_GPS::GPS_OK_FIX_3D;
|
||||
}
|
||||
@ -413,7 +413,7 @@ AP_GPS::highest_supported_status(uint8_t instance) const
|
||||
AP_GPS::GPS_Status
|
||||
AP_GPS::highest_supported_status(void) const
|
||||
{
|
||||
if (drivers[primary_instance] != NULL)
|
||||
if (drivers[primary_instance] != nullptr)
|
||||
return drivers[primary_instance]->highest_supported_status();
|
||||
return AP_GPS::GPS_OK_FIX_3D;
|
||||
}
|
||||
@ -440,7 +440,7 @@ AP_GPS::update_instance(uint8_t instance)
|
||||
return;
|
||||
}
|
||||
|
||||
if (drivers[instance] == NULL || state[instance].status == NO_GPS) {
|
||||
if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
|
||||
// we don't yet know the GPS type of this one, or it has timed
|
||||
// out and needs to be re-initialised
|
||||
detect_instance(instance);
|
||||
@ -463,7 +463,7 @@ AP_GPS::update_instance(uint8_t instance)
|
||||
// free the driver before we run the next detection, so we
|
||||
// don't end up with two allocated at any time
|
||||
delete drivers[instance];
|
||||
drivers[instance] = NULL;
|
||||
drivers[instance] = nullptr;
|
||||
memset(&state[instance], 0, sizeof(state[instance]));
|
||||
state[instance].instance = instance;
|
||||
state[instance].status = NO_GPS;
|
||||
@ -544,7 +544,7 @@ AP_GPS::handle_msg(const mavlink_message_t *msg)
|
||||
}
|
||||
uint8_t i;
|
||||
for (i=0; i<num_instances; i++) {
|
||||
if ((drivers[i] != NULL) && (_type[i] != GPS_TYPE_NONE)) {
|
||||
if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
|
||||
drivers[i]->handle_msg(msg);
|
||||
}
|
||||
}
|
||||
@ -634,7 +634,7 @@ AP_GPS::inject_data(uint8_t *data, uint8_t len)
|
||||
void
|
||||
AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint8_t len)
|
||||
{
|
||||
if (instance < GPS_MAX_INSTANCES && drivers[instance] != NULL)
|
||||
if (instance < GPS_MAX_INSTANCES && drivers[instance] != nullptr)
|
||||
drivers[instance]->inject_data(data, len);
|
||||
}
|
||||
|
||||
@ -704,7 +704,7 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
||||
void
|
||||
AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan)
|
||||
{
|
||||
if (drivers[0] != NULL && drivers[0]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (drivers[0] != nullptr && drivers[0]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
|
||||
drivers[0]->send_mavlink_gps_rtk(chan);
|
||||
}
|
||||
}
|
||||
@ -712,7 +712,7 @@ AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan)
|
||||
void
|
||||
AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan)
|
||||
{
|
||||
if (drivers[1] != NULL && drivers[1]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (drivers[1] != nullptr && drivers[1]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
|
||||
drivers[1]->send_mavlink_gps_rtk(chan);
|
||||
}
|
||||
}
|
||||
@ -721,7 +721,7 @@ uint8_t
|
||||
AP_GPS::first_unconfigured_gps(void) const
|
||||
{
|
||||
for(int i = 0; i < GPS_MAX_INSTANCES; i++) {
|
||||
if(_type[i] != GPS_TYPE_NONE && (drivers[i] == NULL || !drivers[i]->is_configured())) {
|
||||
if(_type[i] != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
@ -731,7 +731,7 @@ AP_GPS::first_unconfigured_gps(void) const
|
||||
void
|
||||
AP_GPS::broadcast_first_configuration_failure_reason(void) const {
|
||||
uint8_t unconfigured = first_unconfigured_gps();
|
||||
if (drivers[unconfigured] == NULL) {
|
||||
if (drivers[unconfigured] == nullptr) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
|
||||
} else {
|
||||
drivers[unconfigured]->broadcast_configuration_failure_reason();
|
||||
@ -835,7 +835,7 @@ void AP_GPS::inject_data_all(const uint8_t *data, uint16_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i=0; i<num_instances; i++) {
|
||||
if ((drivers[i] != NULL) && (_type[i] != GPS_TYPE_NONE)) {
|
||||
if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
|
||||
drivers[i]->inject_data(data, len);
|
||||
}
|
||||
}
|
||||
|
@ -118,11 +118,11 @@ bool AP_GPS_NMEA::read(void)
|
||||
while (numc--) {
|
||||
char c = port->read();
|
||||
#ifdef NMEA_LOG_PATH
|
||||
static FILE *logf = NULL;
|
||||
if (logf == NULL) {
|
||||
static FILE *logf = nullptr;
|
||||
if (logf == nullptr) {
|
||||
logf = fopen(NMEA_LOG_PATH, "wb");
|
||||
}
|
||||
if (logf != NULL) {
|
||||
if (logf != nullptr) {
|
||||
::fwrite(&c, 1, 1, logf);
|
||||
}
|
||||
#endif
|
||||
|
@ -163,7 +163,7 @@ AP_GPS_SBF::parse(uint8_t temp)
|
||||
void
|
||||
AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp)
|
||||
{
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -387,7 +387,7 @@ void
|
||||
AP_GPS_SBP::logging_log_full_update()
|
||||
{
|
||||
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -408,7 +408,7 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,
|
||||
uint8_t msg_len,
|
||||
uint8_t *msg_buff) {
|
||||
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -68,7 +68,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART
|
||||
noReceivedHdop(true)
|
||||
{
|
||||
// stop any config strings that are pending
|
||||
gps.send_blob_start(state.instance, NULL, 0);
|
||||
gps.send_blob_start(state.instance, nullptr, 0);
|
||||
|
||||
// start the process of updating the GPS rates
|
||||
_request_next_config();
|
||||
@ -114,16 +114,16 @@ AP_GPS_UBLOX::_request_next_config(void)
|
||||
}
|
||||
break;
|
||||
case STEP_POLL_SBAS:
|
||||
_send_message(CLASS_CFG, MSG_CFG_SBAS, NULL, 0);
|
||||
_send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0);
|
||||
break;
|
||||
case STEP_POLL_NAV:
|
||||
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, NULL, 0);
|
||||
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0);
|
||||
break;
|
||||
case STEP_POLL_GNSS:
|
||||
_send_message(CLASS_CFG, MSG_CFG_GNSS, NULL, 0);
|
||||
_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0);
|
||||
break;
|
||||
case STEP_NAV_RATE:
|
||||
_send_message(CLASS_CFG, MSG_CFG_RATE, NULL, 0);
|
||||
_send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0);
|
||||
break;
|
||||
case STEP_POSLLH:
|
||||
if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) {
|
||||
@ -307,7 +307,7 @@ AP_GPS_UBLOX::_request_port(void)
|
||||
// not enough space - do it next time
|
||||
return;
|
||||
}
|
||||
_send_message(CLASS_CFG, MSG_CFG_PRT, NULL, 0);
|
||||
_send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0);
|
||||
}
|
||||
// Ensure there is enough space for the largest possible outgoing message
|
||||
// Process bytes available from the stream
|
||||
@ -462,7 +462,7 @@ AP_GPS_UBLOX::read(void)
|
||||
// Private Methods /////////////////////////////////////////////////////////////
|
||||
void AP_GPS_UBLOX::log_mon_hw(void)
|
||||
{
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
struct log_Ubx1 pkt = {
|
||||
@ -485,7 +485,7 @@ void AP_GPS_UBLOX::log_mon_hw(void)
|
||||
|
||||
void AP_GPS_UBLOX::log_mon_hw2(void)
|
||||
{
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -504,7 +504,7 @@ void AP_GPS_UBLOX::log_mon_hw2(void)
|
||||
#if UBLOX_RXM_RAW_LOGGING
|
||||
void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
|
||||
{
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
@ -529,7 +529,7 @@ void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
|
||||
|
||||
void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
|
||||
{
|
||||
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) {
|
||||
if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
@ -1138,7 +1138,7 @@ reset:
|
||||
void
|
||||
AP_GPS_UBLOX::_request_version(void)
|
||||
{
|
||||
_send_message(CLASS_MON, MSG_MON_VER, NULL, 0);
|
||||
_send_message(CLASS_MON, MSG_MON_VER, nullptr, 0);
|
||||
}
|
||||
|
||||
void
|
||||
|
@ -58,7 +58,7 @@ void setup()
|
||||
|
||||
// Initialize the UART for GPS system
|
||||
serial_manager.init();
|
||||
gps.init(NULL, serial_manager);
|
||||
gps.init(nullptr, serial_manager);
|
||||
}
|
||||
|
||||
void loop()
|
||||
|
@ -152,7 +152,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_PARAM_DEFAULTS_PATH
|
||||
#define HAL_PARAM_DEFAULTS_PATH NULL
|
||||
#define HAL_PARAM_DEFAULTS_PATH nullptr
|
||||
#endif
|
||||
|
||||
#ifndef HAL_HAVE_IMU_HEATER
|
||||
|
@ -55,7 +55,7 @@ uint64_t AP_HAL::Util::get_system_clock_ms() const
|
||||
{
|
||||
#if defined(__APPLE__) && defined(__MACH__)
|
||||
struct timeval ts;
|
||||
gettimeofday(&ts, NULL);
|
||||
gettimeofday(&ts, nullptr);
|
||||
return ((long long)((ts.tv_sec * 1000) + (ts.tv_usec / 1000)));
|
||||
#else
|
||||
struct timespec ts;
|
||||
|
@ -18,8 +18,8 @@ public:
|
||||
void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
|
||||
uint64_t get_capabilities() const { return capabilities; }
|
||||
|
||||
virtual const char* get_custom_log_directory() { return NULL; }
|
||||
virtual const char* get_custom_terrain_directory() const { return NULL; }
|
||||
virtual const char* get_custom_log_directory() { return nullptr; }
|
||||
virtual const char* get_custom_terrain_directory() const { return nullptr; }
|
||||
|
||||
// get path to custom defaults file for AP_Param
|
||||
virtual const char* get_custom_defaults_file() const {
|
||||
@ -86,7 +86,7 @@ public:
|
||||
/*
|
||||
return a stream for access to a system shell, if available
|
||||
*/
|
||||
virtual AP_HAL::Stream *get_shell_stream() { return NULL; }
|
||||
virtual AP_HAL::Stream *get_shell_stream() { return nullptr; }
|
||||
|
||||
/* Support for an imu heating system */
|
||||
virtual void set_imu_temp(float current) {}
|
||||
@ -103,7 +103,7 @@ public:
|
||||
PC_INTERVAL /**< measure the interval between instances of an event */
|
||||
};
|
||||
typedef void *perf_counter_t;
|
||||
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
|
||||
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return nullptr; }
|
||||
virtual void perf_begin(perf_counter_t h) {}
|
||||
virtual void perf_end(perf_counter_t h) {}
|
||||
virtual void perf_count(perf_counter_t h) {}
|
||||
|
@ -15,7 +15,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
*/
|
||||
static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
|
||||
{
|
||||
if (uart == NULL) {
|
||||
if (uart == nullptr) {
|
||||
// that UART doesn't exist on this platform
|
||||
return;
|
||||
}
|
||||
@ -37,7 +37,7 @@ void setup(void)
|
||||
|
||||
static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
|
||||
{
|
||||
if (uart == NULL) {
|
||||
if (uart == nullptr) {
|
||||
// that UART doesn't exist on this platform
|
||||
return;
|
||||
}
|
||||
|
@ -278,7 +278,7 @@ public:
|
||||
}
|
||||
|
||||
// allow array indexing, based on current head. Returns a pointer
|
||||
// to the object or NULL
|
||||
// to the object or nullptr
|
||||
T * operator[](uint16_t i) {
|
||||
if (i >= count) {
|
||||
return nullptr;
|
||||
|
@ -169,7 +169,7 @@ bool SocketAPM::pollin(uint32_t timeout_ms)
|
||||
tv.tv_sec = timeout_ms / 1000;
|
||||
tv.tv_usec = (timeout_ms % 1000) * 1000UL;
|
||||
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
@ -190,7 +190,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms)
|
||||
tv.tv_sec = timeout_ms / 1000;
|
||||
tv.tv_usec = (timeout_ms % 1000) * 1000UL;
|
||||
|
||||
if (select(fd+1, NULL, &fds, NULL, &tv) != 1) {
|
||||
if (select(fd+1, nullptr, &fds, nullptr, &tv) != 1) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
@ -211,12 +211,12 @@ bool SocketAPM::listen(uint16_t backlog)
|
||||
SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
|
||||
{
|
||||
if (!pollin(timeout_ms)) {
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
int newfd = ::accept(fd, NULL, NULL);
|
||||
int newfd = ::accept(fd, nullptr, nullptr);
|
||||
if (newfd == -1) {
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
// turn off nagle for lower latency
|
||||
int one = 1;
|
||||
|
@ -506,7 +506,7 @@ int main(int argc, const char *argv[])
|
||||
tv.tv_usec = 0;
|
||||
|
||||
// check if any bytes are available
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -57,7 +57,7 @@ GetOptLong::GetOptLong(int _argc, char *const _argv[], const char *_optstring, c
|
||||
optind(1),
|
||||
optopt(0),
|
||||
longindex(-1),
|
||||
optarg(NULL),
|
||||
optarg(nullptr),
|
||||
argc(_argc),
|
||||
argv(_argv),
|
||||
optstring(_optstring),
|
||||
@ -106,7 +106,7 @@ int GetOptLong::getoption(void)
|
||||
place++;
|
||||
|
||||
namelen = strcspn(place, "=");
|
||||
for (i = 0; longopts[i].name != NULL; i++)
|
||||
for (i = 0; longopts[i].name != nullptr; i++)
|
||||
{
|
||||
if (strlen(longopts[i].name) == namelen
|
||||
&& strncmp(place, longopts[i].name, namelen) == 0)
|
||||
@ -135,7 +135,7 @@ int GetOptLong::getoption(void)
|
||||
}
|
||||
else
|
||||
{
|
||||
optarg = NULL;
|
||||
optarg = nullptr;
|
||||
if (place[namelen] != 0)
|
||||
{
|
||||
/* XXX error? */
|
||||
@ -148,7 +148,7 @@ int GetOptLong::getoption(void)
|
||||
|
||||
place = "";
|
||||
|
||||
if (longopts[i].flag == NULL)
|
||||
if (longopts[i].flag == nullptr)
|
||||
return longopts[i].val;
|
||||
else
|
||||
{
|
||||
@ -183,7 +183,7 @@ int GetOptLong::getoption(void)
|
||||
|
||||
if (oli[1] != ':')
|
||||
{ /* don't need argument */
|
||||
optarg = NULL;
|
||||
optarg = nullptr;
|
||||
if (!*place)
|
||||
++optind;
|
||||
}
|
||||
|
@ -218,7 +218,7 @@ int main(int argc, const char *argv[])
|
||||
tv.tv_usec = 0;
|
||||
|
||||
// check if any bytes are available
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -27,9 +27,9 @@ HAL_Empty::HAL_Empty() :
|
||||
&uartADriver,
|
||||
&uartBDriver,
|
||||
&uartCDriver,
|
||||
NULL, /* no uartD */
|
||||
NULL, /* no uartE */
|
||||
NULL, /* no uartF */
|
||||
nullptr, /* no uartD */
|
||||
nullptr, /* no uartE */
|
||||
nullptr, /* no uartF */
|
||||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
&storageDriver,
|
||||
|
@ -50,14 +50,14 @@ AnalogIn_ADS1115::AnalogIn_ADS1115()
|
||||
AP_HAL::AnalogSource* AnalogIn_ADS1115::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == NULL) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_ADS1115(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
|
||||
hal.console->println("Out of analog channels");
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void AnalogIn_ADS1115::init()
|
||||
@ -83,7 +83,7 @@ void AnalogIn_ADS1115::_update()
|
||||
for (uint8_t j=0; j < rc; j++) {
|
||||
AnalogSource_ADS1115 *source = _channels[j];
|
||||
|
||||
if (source != NULL && reports[i].id == source->_pin) {
|
||||
if (source != nullptr && reports[i].id == source->_pin) {
|
||||
source->_value = reports[i].data / 1000;
|
||||
}
|
||||
}
|
||||
|
@ -61,14 +61,14 @@ float AnalogIn_Raspilot::board_voltage(void)
|
||||
AP_HAL::AnalogSource* AnalogIn_Raspilot::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == NULL) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource_Raspilot(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
|
||||
hal.console->println("Out of analog channels");
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void AnalogIn_Raspilot::init()
|
||||
@ -125,7 +125,7 @@ void AnalogIn_Raspilot::_update()
|
||||
for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) {
|
||||
AnalogSource_Raspilot *source = _channels[j];
|
||||
|
||||
if (source != NULL && i == source->_pin) {
|
||||
if (source != nullptr && i == source->_pin) {
|
||||
source->_value = rx.regs[i] * 3.3 / 4096.0;
|
||||
}
|
||||
}
|
||||
|
@ -197,7 +197,7 @@ void CameraSensor_Mt9v117::_write_reg32(uint16_t reg, uint32_t val)
|
||||
buf[4] = (uint8_t) ((val >> 8) & 0xFF);
|
||||
buf[5] = (uint8_t) (val & 0xFF);
|
||||
|
||||
if (!_dev->transfer(buf, 6, NULL, 0)) {
|
||||
if (!_dev->transfer(buf, 6, nullptr, 0)) {
|
||||
hal.console->printf("mt9v117: error writing 0x%8x\n", reg);
|
||||
}
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ void GPIO_RPI::init()
|
||||
|
||||
// mmap GPIO
|
||||
void *gpio_map = mmap(
|
||||
NULL, // Any adddress in our space will do
|
||||
nullptr, // Any adddress in our space will do
|
||||
BLOCK_SIZE, // Map length
|
||||
PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
|
||||
MAP_SHARED, // Shared with other processes
|
||||
|
@ -68,7 +68,7 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
left = (HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH -
|
||||
HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT) / 2;
|
||||
|
||||
if (device_path == NULL ||
|
||||
if (device_path == nullptr ||
|
||||
!_videoin->open_device(device_path, memtype)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't open "
|
||||
"video device");
|
||||
@ -170,7 +170,7 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
|
||||
/* Create the thread that will be waiting for frames
|
||||
* Initialize thread and mutex */
|
||||
ret = pthread_mutex_init(&_mutex, NULL);
|
||||
ret = pthread_mutex_init(&_mutex, nullptr);
|
||||
if (ret != 0) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: failed to init mutex");
|
||||
}
|
||||
@ -222,7 +222,7 @@ void *OpticalFlow_Onboard::_read_thread(void *arg)
|
||||
OpticalFlow_Onboard *optflow_onboard = (OpticalFlow_Onboard *) arg;
|
||||
|
||||
optflow_onboard->_run_optflow();
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void OpticalFlow_Onboard::_run_optflow()
|
||||
@ -235,7 +235,7 @@ void OpticalFlow_Onboard::_run_optflow()
|
||||
uint32_t crop_left = 0, crop_top = 0;
|
||||
uint32_t shrink_scale = 0, shrink_width = 0, shrink_height = 0;
|
||||
uint32_t shrink_width_offset = 0, shrink_height_offset = 0;
|
||||
uint8_t *convert_buffer = NULL, *output_buffer = NULL;
|
||||
uint8_t *convert_buffer = nullptr, *output_buffer = nullptr;
|
||||
uint8_t qual;
|
||||
|
||||
if (_format == V4L2_PIX_FMT_YUYV) {
|
||||
@ -330,7 +330,7 @@ void OpticalFlow_Onboard::_run_optflow()
|
||||
|
||||
/* if it is at least the second frame we receive
|
||||
* since we have to compare 2 frames */
|
||||
if (_last_video_frame.data == NULL) {
|
||||
if (_last_video_frame.data == nullptr) {
|
||||
_last_video_frame = video_frame;
|
||||
continue;
|
||||
}
|
||||
|
@ -39,8 +39,8 @@ PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
||||
, _duty_path(duty_path)
|
||||
, _period_path(period_path)
|
||||
{
|
||||
if (_export_path == NULL || _enable_path == NULL ||
|
||||
_period_path == NULL || _duty_path == NULL) {
|
||||
if (_export_path == nullptr || _enable_path == nullptr ||
|
||||
_period_path == nullptr || _duty_path == nullptr) {
|
||||
AP_HAL::panic("PWM_Sysfs: export=%p enable=%p period=%p duty=%p"
|
||||
" required path is NULL", _export_path, _enable_path,
|
||||
_period_path, _duty_path);
|
||||
@ -269,7 +269,7 @@ char *PWM_Sysfs_Bebop::_generate_period_path(uint8_t channel)
|
||||
|
||||
PWM_Sysfs_Bebop::PWM_Sysfs_Bebop(uint8_t channel) :
|
||||
PWM_Sysfs_Base(_generate_export_path(),
|
||||
NULL,
|
||||
nullptr,
|
||||
_generate_enable_path(channel),
|
||||
_generate_duty_path(channel),
|
||||
_generate_period_path(channel),
|
||||
|
@ -46,11 +46,11 @@ protected:
|
||||
private:
|
||||
uint32_t _nsec_duty_cycle_value = 0;
|
||||
int _duty_cycle_fd = -1;
|
||||
char *_export_path = NULL;
|
||||
char *_polarity_path = NULL;
|
||||
char *_enable_path = NULL;
|
||||
char *_duty_path = NULL;
|
||||
char *_period_path = NULL;
|
||||
char *_export_path = nullptr;
|
||||
char *_polarity_path = nullptr;
|
||||
char *_enable_path = nullptr;
|
||||
char *_duty_path = nullptr;
|
||||
char *_period_path = nullptr;
|
||||
};
|
||||
|
||||
class PWM_Sysfs : public PWM_Sysfs_Base {
|
||||
|
@ -320,7 +320,7 @@ void RCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
#if 0
|
||||
// useful for debugging
|
||||
static FILE *rclog;
|
||||
if (rclog == NULL) {
|
||||
if (rclog == nullptr) {
|
||||
rclog = fopen("/tmp/rcin.log", "w");
|
||||
}
|
||||
if (rclog) {
|
||||
|
@ -87,7 +87,7 @@ void RCInput_115200::_timer_tick(void)
|
||||
tv.tv_usec = 0;
|
||||
|
||||
// check if any bytes are available
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -150,7 +150,7 @@ Memory_table::~Memory_table()
|
||||
void* Memory_table::get_page(void** const pages, uint32_t addr) const
|
||||
{
|
||||
if (addr >= PAGE_SIZE * _page_count) {
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return (uint8_t*)pages[(uint32_t) addr / 4096] + addr % 4096;
|
||||
}
|
||||
@ -166,7 +166,7 @@ void* Memory_table::get_virt_addr(const uint32_t phys_addr) const
|
||||
return (void*) ((uintptr_t) _virt_pages[i] + (phys_addr & 0xFFF));
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// FIXME: in-congruent function style see above
|
||||
@ -221,9 +221,9 @@ void* RCInput_RPI::map_peripheral(uint32_t base, uint32_t len)
|
||||
|
||||
if (fd < 0) {
|
||||
printf("Failed to open /dev/mem: %m\n");
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
vaddr = mmap(NULL, len, PROT_READ|PROT_WRITE, MAP_SHARED, fd, base);
|
||||
vaddr = mmap(nullptr, len, PROT_READ|PROT_WRITE, MAP_SHARED, fd, base);
|
||||
if (vaddr == MAP_FAILED) {
|
||||
printf("rpio-pwm: Failed to map peripheral at 0x%08x: %m\n", base);
|
||||
}
|
||||
@ -472,7 +472,7 @@ void RCInput_RPI::_timer_tick()
|
||||
dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8]);
|
||||
for(j = 1; j >= -1; j--){
|
||||
x = circle_buffer->get_virt_addr((ad + j)->dst);
|
||||
if(x != NULL) {
|
||||
if(x != nullptr) {
|
||||
break;}
|
||||
}
|
||||
|
||||
|
@ -100,7 +100,7 @@ void RCInput_SBUS::_timer_tick(void)
|
||||
|
||||
// as VMIN is SBUS_FRAME_SIZE the select won't return unless there is
|
||||
// at least SBUS_FRAME_SIZE bytes available
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -301,7 +301,7 @@ void RCOutput_Bebop::init()
|
||||
pthread_condattr_t cond_attr;
|
||||
|
||||
/* Initialize thread, cond, and mutex */
|
||||
ret = pthread_mutex_init(&_mutex, NULL);
|
||||
ret = pthread_mutex_init(&_mutex, nullptr);
|
||||
if (ret != 0) {
|
||||
perror("RCout_Bebop: failed to init mutex\n");
|
||||
return;
|
||||
@ -419,7 +419,7 @@ void* RCOutput_Bebop::_control_thread(void *arg) {
|
||||
RCOutput_Bebop* rcout = (RCOutput_Bebop *) arg;
|
||||
|
||||
rcout->_run_rcout();
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void RCOutput_Bebop::_run_rcout()
|
||||
|
@ -61,7 +61,7 @@ RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
uint8_t channel_offset,
|
||||
int16_t oe_pin_number) :
|
||||
_dev(std::move(dev)),
|
||||
_enable_pin(NULL),
|
||||
_enable_pin(nullptr),
|
||||
_frequency(50),
|
||||
_pulses_buffer(new uint16_t[PWM_CHAN_COUNT - channel_offset]),
|
||||
_external_clock(external_clock),
|
||||
|
@ -55,7 +55,7 @@ void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
//hal.console->printf("[RPIOUARTDriver]: begin \n");
|
||||
|
||||
if (device_path != NULL) {
|
||||
if (device_path != nullptr) {
|
||||
UARTDriver::begin(b,rxS,txS);
|
||||
if ( is_initialized()) {
|
||||
_external = true;
|
||||
|
@ -27,7 +27,7 @@ SPIUARTDriver::SPIUARTDriver()
|
||||
|
||||
void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
if (device_path != NULL) {
|
||||
if (device_path != nullptr) {
|
||||
UARTDriver::begin(b, rxS, txS);
|
||||
if (is_initialized()) {
|
||||
_external = true;
|
||||
@ -52,10 +52,10 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
_readbuf.set_size(rxS);
|
||||
_writebuf.set_size(txS);
|
||||
|
||||
if (_buffer == NULL) {
|
||||
if (_buffer == nullptr) {
|
||||
/* Do not allocate new buffer, if we're just changing speed */
|
||||
_buffer = new uint8_t[rxS];
|
||||
if (_buffer == NULL) {
|
||||
if (_buffer == nullptr) {
|
||||
hal.console->printf("Not enough memory\n");
|
||||
AP_HAL::panic("Not enough memory\n");
|
||||
}
|
||||
|
@ -323,7 +323,7 @@ void Scheduler::_timer_task()
|
||||
_timer_semaphore.give();
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
if (_failsafe != nullptr) {
|
||||
_failsafe();
|
||||
}
|
||||
|
||||
|
@ -11,7 +11,7 @@ namespace Linux {
|
||||
class Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
pthread_mutex_init(&_lock, nullptr);
|
||||
}
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
|
@ -18,15 +18,15 @@ TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port, bool wait):
|
||||
|
||||
TCPServerDevice::~TCPServerDevice()
|
||||
{
|
||||
if (sock != NULL) {
|
||||
if (sock != nullptr) {
|
||||
delete sock;
|
||||
sock = NULL;
|
||||
sock = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n)
|
||||
{
|
||||
if (sock == NULL) {
|
||||
if (sock == nullptr) {
|
||||
return -1;
|
||||
}
|
||||
return sock->send(buf, n);
|
||||
@ -38,20 +38,20 @@ ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n)
|
||||
*/
|
||||
ssize_t TCPServerDevice::read(uint8_t *buf, uint16_t n)
|
||||
{
|
||||
if (sock == NULL) {
|
||||
if (sock == nullptr) {
|
||||
sock = listener.accept(0);
|
||||
if (sock != NULL) {
|
||||
if (sock != nullptr) {
|
||||
sock->set_blocking(_blocking);
|
||||
}
|
||||
}
|
||||
if (sock == NULL) {
|
||||
if (sock == nullptr) {
|
||||
return -1;
|
||||
}
|
||||
ssize_t ret = sock->recv(buf, n, 1);
|
||||
if (ret == 0) {
|
||||
// EOF, go back to waiting for a new connection
|
||||
delete sock;
|
||||
sock = NULL;
|
||||
sock = nullptr;
|
||||
return -1;
|
||||
}
|
||||
return ret;
|
||||
@ -89,7 +89,7 @@ bool TCPServerDevice::open()
|
||||
::printf("Waiting for connection on %s:%u ....\n",
|
||||
_ip, (unsigned)_port);
|
||||
::fflush(stdout);
|
||||
while (sock == NULL) {
|
||||
while (sock == nullptr) {
|
||||
sock = listener.accept(1000);
|
||||
}
|
||||
sock->set_blocking(_blocking);
|
||||
@ -102,9 +102,9 @@ bool TCPServerDevice::open()
|
||||
|
||||
bool TCPServerDevice::close()
|
||||
{
|
||||
if (sock != NULL) {
|
||||
if (sock != nullptr) {
|
||||
delete sock;
|
||||
sock = NULL;
|
||||
sock = nullptr;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
|
||||
private:
|
||||
SocketAPM listener{false};
|
||||
SocketAPM *sock = NULL;
|
||||
SocketAPM *sock = nullptr;
|
||||
const char *_ip;
|
||||
uint16_t _port;
|
||||
bool _wait;
|
||||
|
@ -73,7 +73,7 @@ bool ToneAlarm_Raspilot::init()
|
||||
|
||||
// mmap GPIO
|
||||
void *pwm_map = mmap(
|
||||
NULL, // Any adddress in our space will do
|
||||
nullptr, // Any adddress in our space will do
|
||||
BLOCK_SIZE, // Map length
|
||||
PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
|
||||
MAP_SHARED, // Shared with other processes
|
||||
@ -82,7 +82,7 @@ bool ToneAlarm_Raspilot::init()
|
||||
);
|
||||
|
||||
void *clk_map = mmap(
|
||||
NULL, // Any adddress in our space will do
|
||||
nullptr, // Any adddress in our space will do
|
||||
BLOCK_SIZE, // Map length
|
||||
PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
|
||||
MAP_SHARED, // Shared with other processes
|
||||
|
@ -32,7 +32,7 @@ extern const AP_HAL::HAL& hal;
|
||||
using namespace Linux;
|
||||
|
||||
UARTDriver::UARTDriver(bool default_console) :
|
||||
device_path(NULL),
|
||||
device_path(nullptr),
|
||||
_packetise(false),
|
||||
_device{new ConsoleDevice()}
|
||||
{
|
||||
@ -60,10 +60,10 @@ void UARTDriver::begin(uint32_t b)
|
||||
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
{
|
||||
if (!_initialised) {
|
||||
if (device_path == NULL && _console) {
|
||||
if (device_path == nullptr && _console) {
|
||||
_device = new ConsoleDevice();
|
||||
} else {
|
||||
if (device_path == NULL) {
|
||||
if (device_path == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -139,38 +139,38 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
|
||||
|
||||
char *devstr = strdup(arg);
|
||||
|
||||
if (devstr == NULL) {
|
||||
if (devstr == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
char *saveptr = NULL;
|
||||
char *saveptr = nullptr;
|
||||
char *protocol, *ip, *port, *flag;
|
||||
|
||||
protocol = strtok_r(devstr, ":", &saveptr);
|
||||
ip = strtok_r(NULL, ":", &saveptr);
|
||||
port = strtok_r(NULL, ":", &saveptr);
|
||||
flag = strtok_r(NULL, ":", &saveptr);
|
||||
ip = strtok_r(nullptr, ":", &saveptr);
|
||||
port = strtok_r(nullptr, ":", &saveptr);
|
||||
flag = strtok_r(nullptr, ":", &saveptr);
|
||||
|
||||
if (ip == NULL || port == NULL) {
|
||||
if (ip == nullptr || port == nullptr) {
|
||||
free(devstr);
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (_ip) {
|
||||
free(_ip);
|
||||
_ip = NULL;
|
||||
_ip = nullptr;
|
||||
}
|
||||
|
||||
if (_flag) {
|
||||
free(_flag);
|
||||
_flag = NULL;
|
||||
_flag = nullptr;
|
||||
}
|
||||
|
||||
_base_port = (uint16_t) atoi(port);
|
||||
_ip = strdup(ip);
|
||||
|
||||
/* Optional flag for TCP */
|
||||
if (flag != NULL) {
|
||||
if (flag != nullptr) {
|
||||
_flag = strdup(flag);
|
||||
}
|
||||
|
||||
|
@ -186,16 +186,16 @@ int Util::get_hw_arm32()
|
||||
{
|
||||
char buffer[MAX_SIZE_LINE] = { 0 };
|
||||
FILE *f = fopen("/proc/cpuinfo", "r");
|
||||
if (f == NULL) {
|
||||
if (f == nullptr) {
|
||||
return -errno;
|
||||
}
|
||||
|
||||
while (fgets(buffer, MAX_SIZE_LINE, f) != NULL) {
|
||||
if (strstr(buffer, "Hardware") == NULL) {
|
||||
while (fgets(buffer, MAX_SIZE_LINE, f) != nullptr) {
|
||||
if (strstr(buffer, "Hardware") == nullptr) {
|
||||
continue;
|
||||
}
|
||||
for (uint8_t i = 0; i < UTIL_NUM_HARDWARES; i++) {
|
||||
if (strstr(buffer, _hw_names[i]) == NULL) {
|
||||
if (strstr(buffer, _hw_names[i]) == nullptr) {
|
||||
continue;
|
||||
}
|
||||
fclose(f);
|
||||
|
@ -105,8 +105,8 @@ private:
|
||||
Heat *_heat;
|
||||
int saved_argc;
|
||||
char* const *saved_argv;
|
||||
const char* custom_log_directory = NULL;
|
||||
const char* custom_terrain_directory = NULL;
|
||||
const char* custom_log_directory = nullptr;
|
||||
const char* custom_terrain_directory = nullptr;
|
||||
static const char *_hw_names[UTIL_NUM_HARDWARES];
|
||||
};
|
||||
|
||||
|
@ -67,7 +67,7 @@ bool VideoIn::open_device(const char *device_path, uint32_t memtype)
|
||||
int ret;
|
||||
|
||||
_fd = -1;
|
||||
_buffers = NULL;
|
||||
_buffers = nullptr;
|
||||
_fd = open(device_path, O_RDWR);
|
||||
_memtype = memtype;
|
||||
if (_fd < 0) {
|
||||
@ -115,7 +115,7 @@ bool VideoIn::allocate_buffers(uint32_t nbufs)
|
||||
}
|
||||
|
||||
buffers = (struct buffer *)malloc(rb.count * sizeof buffers[0]);
|
||||
if (buffers == NULL) {
|
||||
if (buffers == nullptr) {
|
||||
hal.console->printf("Unable to allocate buffers\n");
|
||||
return false;
|
||||
}
|
||||
|
@ -25,7 +25,7 @@ int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv) {
|
||||
}
|
||||
|
||||
static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel) {
|
||||
AP_HAL::DigitalSource *ch = NULL;
|
||||
AP_HAL::DigitalSource *ch = nullptr;
|
||||
int pin = parse_gpio_pin_number(argc, argv);
|
||||
|
||||
if (pin <= 0) return -1;
|
||||
@ -46,7 +46,7 @@ static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_chan
|
||||
}
|
||||
|
||||
static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel) {
|
||||
AP_HAL::DigitalSource *ch = NULL;
|
||||
AP_HAL::DigitalSource *ch = nullptr;
|
||||
int pin = parse_gpio_pin_number(argc, argv);
|
||||
|
||||
if (pin <= 0) return -1;
|
||||
|
@ -129,7 +129,7 @@ static void *mpu_data_ready(void *ctx)
|
||||
|
||||
int ret = mpu9x50_get_data(&data);
|
||||
if (ret != 0) {
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
DSPBuffer::IMU::BUF b;
|
||||
b.timestamp = data.timestamp;
|
||||
@ -163,7 +163,7 @@ static void *mpu_data_ready(void *ctx)
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
static void mpu9250_startup(void)
|
||||
@ -172,7 +172,7 @@ static void mpu9250_startup(void)
|
||||
if (init_mpu9250() != 0) {
|
||||
return;
|
||||
}
|
||||
mpu9x50_register_interrupt(65, mpu_data_ready, NULL);
|
||||
mpu9x50_register_interrupt(65, mpu_data_ready, nullptr);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -257,7 +257,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
struct adc_msg_s buf_adc[PX4_ANALOG_MAX_CHANNELS];
|
||||
|
||||
// cope with initial setup of stop pin
|
||||
if (_channels[_current_stop_pin_i] == NULL ||
|
||||
if (_channels[_current_stop_pin_i] == nullptr ||
|
||||
_channels[_current_stop_pin_i]->_stop_pin == -1) {
|
||||
next_stop_pin();
|
||||
}
|
||||
@ -281,7 +281,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
(unsigned)buf_adc[i].am_data);
|
||||
for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
|
||||
PX4::PX4AnalogSource *c = _channels[j];
|
||||
if (c != NULL && buf_adc[i].am_channel == c->_pin) {
|
||||
if (c != nullptr && buf_adc[i].am_channel == c->_pin) {
|
||||
// add a value if either there is no stop pin, or
|
||||
// the stop pin has been settling for enough time
|
||||
if (c->_stop_pin == -1 ||
|
||||
@ -308,7 +308,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
_battery_timestamp = battery.timestamp;
|
||||
for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
|
||||
PX4::PX4AnalogSource *c = _channels[j];
|
||||
if (c == NULL) continue;
|
||||
if (c == nullptr) continue;
|
||||
if (c->_pin == PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN) {
|
||||
c->_add_value(battery.voltage_v / PX4_VOLTAGE_SCALING, 0);
|
||||
}
|
||||
@ -335,7 +335,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
_servorail_voltage = servorail.voltage_v;
|
||||
for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
|
||||
PX4::PX4AnalogSource *c = _channels[j];
|
||||
if (c == NULL) continue;
|
||||
if (c == nullptr) continue;
|
||||
if (c->_pin == PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN) {
|
||||
c->_add_value(servorail.voltage_v / PX4_VOLTAGE_SCALING, 0);
|
||||
}
|
||||
@ -373,13 +373,13 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
AP_HAL::AnalogSource* PX4AnalogIn::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
|
||||
if (_channels[j] == NULL) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new PX4AnalogSource(pin, 0.0f);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
hal.console->println("Out of analog channels");
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -91,7 +91,7 @@ HAL_PX4::HAL_PX4() :
|
||||
&rcoutDriver, /* rcoutput */
|
||||
&schedulerInstance, /* scheduler */
|
||||
&utilInstance, /* util */
|
||||
NULL) /* no onboard optical flow */
|
||||
nullptr) /* no onboard optical flow */
|
||||
{}
|
||||
|
||||
bool _px4_thread_should_exit = false; /**< Daemon exit flag */
|
||||
@ -170,7 +170,7 @@ static int main_loop(int argc, char **argv)
|
||||
will only ever be called if a loop() call runs for more than
|
||||
0.1 second
|
||||
*/
|
||||
hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL);
|
||||
hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr);
|
||||
|
||||
g_callbacks->loop();
|
||||
|
||||
@ -248,7 +248,7 @@ void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
APM_MAIN_PRIORITY,
|
||||
APM_MAIN_THREAD_STACK_SIZE,
|
||||
main_loop,
|
||||
NULL);
|
||||
nullptr);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -31,7 +31,7 @@ void NSHShellStream::shell_thread(void *arg)
|
||||
dup2(nsh->child.out, 1);
|
||||
dup2(nsh->child.out, 2);
|
||||
|
||||
nsh_consolemain(0, NULL);
|
||||
nsh_consolemain(0, nullptr);
|
||||
|
||||
nsh->shell_stdin = -1;
|
||||
nsh->shell_stdout = -1;
|
||||
|
@ -20,7 +20,7 @@ void PX4RCInput::init()
|
||||
AP_HAL::panic("Unable to subscribe to input_rc");
|
||||
}
|
||||
clear_overrides();
|
||||
pthread_mutex_init(&rcin_mutex, NULL);
|
||||
pthread_mutex_init(&rcin_mutex, nullptr);
|
||||
}
|
||||
|
||||
bool PX4RCInput::new_input()
|
||||
|
@ -71,10 +71,10 @@ void PX4RCOutput::init()
|
||||
}
|
||||
|
||||
// publish actuator vaules on demand
|
||||
_actuator_direct_pub = NULL;
|
||||
_actuator_direct_pub = nullptr;
|
||||
|
||||
// and armed state
|
||||
_actuator_armed_pub = NULL;
|
||||
_actuator_armed_pub = nullptr;
|
||||
}
|
||||
|
||||
|
||||
@ -391,7 +391,7 @@ void PX4RCOutput::_arm_actuators(bool arm)
|
||||
_armed.lockdown = false;
|
||||
_armed.force_failsafe = false;
|
||||
|
||||
if (_actuator_armed_pub == NULL) {
|
||||
if (_actuator_armed_pub == nullptr) {
|
||||
_actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed);
|
||||
@ -433,7 +433,7 @@ void PX4RCOutput::_publish_actuators(void)
|
||||
actuators.values[i] = actuators.values[i]*2 - 1;
|
||||
}
|
||||
|
||||
if (_actuator_direct_pub == NULL) {
|
||||
if (_actuator_direct_pub == nullptr) {
|
||||
_actuator_direct_pub = orb_advertise(ORB_ID(actuator_direct), &actuators);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_direct), _actuator_direct_pub, &actuators);
|
||||
|
@ -58,8 +58,8 @@ private:
|
||||
} _outputs[ORB_MULTI_MAX_INSTANCES] {};
|
||||
actuator_armed_s _armed;
|
||||
|
||||
orb_advert_t _actuator_direct_pub = NULL;
|
||||
orb_advert_t _actuator_armed_pub = NULL;
|
||||
orb_advert_t _actuator_direct_pub = nullptr;
|
||||
orb_advert_t _actuator_armed_pub = nullptr;
|
||||
uint16_t _esc_pwm_min = 0;
|
||||
uint16_t _esc_pwm_max = 0;
|
||||
|
||||
|
@ -133,7 +133,7 @@ void PX4Scheduler::delay_microseconds_boost(uint16_t usec)
|
||||
sem_init(&wait_semaphore, 0, 0);
|
||||
hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore);
|
||||
sem_wait(&wait_semaphore);
|
||||
hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, NULL);
|
||||
hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, nullptr);
|
||||
}
|
||||
|
||||
void PX4Scheduler::delay(uint16_t ms)
|
||||
@ -249,7 +249,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
}
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
if (_failsafe != nullptr) {
|
||||
_failsafe();
|
||||
}
|
||||
|
||||
@ -267,7 +267,7 @@ void *PX4Scheduler::_timer_thread(void *arg)
|
||||
uint32_t last_ran_overtime = 0;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
poll(nullptr, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
sched->delay_microseconds_semaphore(1000);
|
||||
@ -291,7 +291,7 @@ void *PX4Scheduler::_timer_thread(void *arg)
|
||||
#endif
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void PX4Scheduler::_run_io(void)
|
||||
@ -318,7 +318,7 @@ void *PX4Scheduler::_uart_thread(void *arg)
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
poll(nullptr, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
sched->delay_microseconds_semaphore(1000);
|
||||
@ -331,7 +331,7 @@ void *PX4Scheduler::_uart_thread(void *arg)
|
||||
((PX4UARTDriver *)hal.uartE)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartF)->_timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void *PX4Scheduler::_io_thread(void *arg)
|
||||
@ -339,17 +339,17 @@ void *PX4Scheduler::_io_thread(void *arg)
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
poll(nullptr, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
poll(NULL, 0, 1);
|
||||
poll(nullptr, 0, 1);
|
||||
|
||||
// run registered IO processes
|
||||
perf_begin(sched->_perf_io_timers);
|
||||
sched->_run_io();
|
||||
perf_end(sched->_perf_io_timers);
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void *PX4Scheduler::_storage_thread(void *arg)
|
||||
@ -357,17 +357,17 @@ void *PX4Scheduler::_storage_thread(void *arg)
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
poll(nullptr, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
poll(NULL, 0, 10);
|
||||
poll(nullptr, 0, 10);
|
||||
|
||||
// process any pending storage writes
|
||||
perf_begin(sched->_perf_storage_timer);
|
||||
((PX4Storage *)hal.storage)->_timer_tick();
|
||||
perf_end(sched->_perf_storage_timer);
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
bool PX4Scheduler::in_timerprocess()
|
||||
|
@ -9,7 +9,7 @@
|
||||
class PX4::Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
pthread_mutex_init(&_lock, nullptr);
|
||||
}
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
|
@ -61,7 +61,7 @@ bool PX4Util::run_debug_shell(AP_HAL::BetterStream *stream)
|
||||
dup2(fd, 1);
|
||||
dup2(fd, 2);
|
||||
|
||||
nsh_consolemain(0, NULL);
|
||||
nsh_consolemain(0, nullptr);
|
||||
|
||||
// this shouldn't happen
|
||||
hal.console->printf("shell exited\n");
|
||||
@ -152,7 +152,7 @@ PX4Util::perf_counter_t PX4Util::perf_alloc(PX4Util::perf_counter_type t, const
|
||||
px4_t = ::PC_INTERVAL;
|
||||
break;
|
||||
default:
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
return (perf_counter_t)::perf_alloc(px4_t, name);
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ HAL_QURT::HAL_QURT() :
|
||||
&uartCDriver,
|
||||
&uartDDriver,
|
||||
&uartEDriver,
|
||||
NULL, // uartF
|
||||
nullptr, // uartF
|
||||
&i2c_mgr_instance,
|
||||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
@ -66,7 +66,7 @@ HAL_QURT::HAL_QURT() :
|
||||
&rcoutDriver,
|
||||
&schedulerInstance,
|
||||
&utilInstance,
|
||||
NULL)
|
||||
nullptr)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -171,7 +171,7 @@ void Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
}
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
if (_failsafe != nullptr) {
|
||||
_failsafe();
|
||||
}
|
||||
|
||||
@ -203,7 +203,7 @@ void *Scheduler::_timer_thread(void *arg)
|
||||
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void Scheduler::_run_io(void)
|
||||
@ -242,7 +242,7 @@ void *Scheduler::_uart_thread(void *arg)
|
||||
((UARTDriver *)hal.uartD)->timer_tick();
|
||||
((UARTDriver *)hal.uartE)->timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void *Scheduler::_io_thread(void *arg)
|
||||
@ -258,7 +258,7 @@ void *Scheduler::_io_thread(void *arg)
|
||||
// run registered IO processes
|
||||
sched->_run_io();
|
||||
}
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
bool Scheduler::in_timerprocess()
|
||||
|
@ -9,7 +9,7 @@
|
||||
class QURT::Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
pthread_mutex_init(&_lock, nullptr);
|
||||
}
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
|
@ -41,7 +41,7 @@ static void *main_thread(void *cmdptr)
|
||||
argv[argc] = nullptr;
|
||||
|
||||
ArduPilot_main(argc, argv);
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
|
||||
|
@ -35,7 +35,7 @@
|
||||
|
||||
void freeifaddrs(struct ifaddrs *ifp)
|
||||
{
|
||||
if (ifp != NULL) {
|
||||
if (ifp != nullptr) {
|
||||
free(ifp->ifa_name);
|
||||
free(ifp->ifa_addr);
|
||||
free(ifp->ifa_netmask);
|
||||
@ -51,8 +51,8 @@ static struct sockaddr *sockaddr_dup(struct sockaddr *sa)
|
||||
socklen_t socklen;
|
||||
socklen = sizeof(struct sockaddr_storage);
|
||||
ret = (struct sockaddr *)calloc(1, socklen);
|
||||
if (ret == NULL)
|
||||
return NULL;
|
||||
if (ret == nullptr)
|
||||
return nullptr;
|
||||
memcpy(ret, sa, socklen);
|
||||
return ret;
|
||||
}
|
||||
@ -67,11 +67,11 @@ int getifaddrs(struct ifaddrs **ifap)
|
||||
struct ifconf ifc;
|
||||
char buff[8192];
|
||||
int fd, i, n;
|
||||
struct ifreq *ifr=NULL;
|
||||
struct ifreq *ifr=nullptr;
|
||||
struct ifaddrs *curif;
|
||||
struct ifaddrs *lastif = NULL;
|
||||
struct ifaddrs *lastif = nullptr;
|
||||
|
||||
*ifap = NULL;
|
||||
*ifap = nullptr;
|
||||
|
||||
if ((fd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) {
|
||||
return -1;
|
||||
@ -98,27 +98,27 @@ int getifaddrs(struct ifaddrs **ifap)
|
||||
}
|
||||
|
||||
curif = (struct ifaddrs *)calloc(1, sizeof(struct ifaddrs));
|
||||
if (curif == NULL) {
|
||||
if (curif == nullptr) {
|
||||
freeifaddrs(*ifap);
|
||||
close(fd);
|
||||
return -1;
|
||||
}
|
||||
curif->ifa_name = strdup(ifr[i].ifr_name);
|
||||
if (curif->ifa_name == NULL) {
|
||||
if (curif->ifa_name == nullptr) {
|
||||
free(curif);
|
||||
freeifaddrs(*ifap);
|
||||
close(fd);
|
||||
return -1;
|
||||
}
|
||||
curif->ifa_flags = ifr[i].ifr_flags;
|
||||
curif->ifa_dstaddr = NULL;
|
||||
curif->ifa_data = NULL;
|
||||
curif->ifa_next = NULL;
|
||||
curif->ifa_dstaddr = nullptr;
|
||||
curif->ifa_data = nullptr;
|
||||
curif->ifa_next = nullptr;
|
||||
|
||||
curif->ifa_addr = NULL;
|
||||
curif->ifa_addr = nullptr;
|
||||
if (ioctl(fd, SIOCGIFADDR, &ifr[i]) != -1) {
|
||||
curif->ifa_addr = sockaddr_dup(&ifr[i].ifr_addr);
|
||||
if (curif->ifa_addr == NULL) {
|
||||
if (curif->ifa_addr == nullptr) {
|
||||
free(curif->ifa_name);
|
||||
free(curif);
|
||||
freeifaddrs(*ifap);
|
||||
@ -127,11 +127,11 @@ int getifaddrs(struct ifaddrs **ifap)
|
||||
}
|
||||
}
|
||||
|
||||
curif->ifa_netmask = NULL;
|
||||
curif->ifa_netmask = nullptr;
|
||||
if (ioctl(fd, SIOCGIFNETMASK, &ifr[i]) != -1) {
|
||||
curif->ifa_netmask = sockaddr_dup(&ifr[i].ifr_addr);
|
||||
if (curif->ifa_netmask == NULL) {
|
||||
if (curif->ifa_addr != NULL) {
|
||||
if (curif->ifa_netmask == nullptr) {
|
||||
if (curif->ifa_addr != nullptr) {
|
||||
free(curif->ifa_addr);
|
||||
}
|
||||
free(curif->ifa_name);
|
||||
@ -142,7 +142,7 @@ int getifaddrs(struct ifaddrs **ifap)
|
||||
}
|
||||
}
|
||||
|
||||
if (lastif == NULL) {
|
||||
if (lastif == nullptr) {
|
||||
*ifap = curif;
|
||||
} else {
|
||||
lastif->ifa_next = curif;
|
||||
@ -157,9 +157,9 @@ int getifaddrs(struct ifaddrs **ifap)
|
||||
|
||||
const char *get_ipv4_broadcast(void)
|
||||
{
|
||||
struct ifaddrs *ifap = NULL;
|
||||
struct ifaddrs *ifap = nullptr;
|
||||
if (getifaddrs(&ifap) != 0) {
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
struct ifaddrs *ia;
|
||||
for (ia=ifap; ia; ia=ia->ifa_next) {
|
||||
@ -175,7 +175,7 @@ const char *get_ipv4_broadcast(void)
|
||||
return ret;
|
||||
}
|
||||
freeifaddrs(ifap);
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
#ifdef MAIN_PROGRAM
|
||||
|
@ -84,7 +84,7 @@ static void get_storage(void)
|
||||
*/
|
||||
static void socket_check(void)
|
||||
{
|
||||
static const char *bcast = NULL;
|
||||
static const char *bcast = nullptr;
|
||||
uint8_t buf[300];
|
||||
ssize_t ret = sock.recv(buf, sizeof(buf), 0);
|
||||
if (ret > 0) {
|
||||
@ -102,9 +102,9 @@ static void socket_check(void)
|
||||
}
|
||||
}
|
||||
uint32_t nbytes;
|
||||
if (bcast == NULL) {
|
||||
if (bcast == nullptr) {
|
||||
bcast = get_ipv4_broadcast();
|
||||
if (bcast == NULL) {
|
||||
if (bcast == nullptr) {
|
||||
bcast = "255.255.255.255";
|
||||
}
|
||||
printf("Broadcasting to %s\n", bcast);
|
||||
|
@ -46,7 +46,7 @@ int vasprintf(char **ptr, const char *format, va_list ap)
|
||||
va_list ap2;
|
||||
|
||||
va_copy(ap2, ap);
|
||||
ret = vsnprintf(NULL, 0, format, ap2);
|
||||
ret = vsnprintf(nullptr, 0, format, ap2);
|
||||
va_end(ap2);
|
||||
if (ret < 0) return ret;
|
||||
|
||||
@ -65,7 +65,7 @@ int asprintf(char **ptr, const char *format, ...)
|
||||
va_list ap;
|
||||
int ret;
|
||||
|
||||
*ptr = NULL;
|
||||
*ptr = nullptr;
|
||||
va_start(ap, format);
|
||||
ret = vasprintf(ptr, format, ap);
|
||||
va_end(ap);
|
||||
|
@ -27,15 +27,15 @@ void SITL_State::_set_param_default(const char *parm)
|
||||
{
|
||||
char *pdup = strdup(parm);
|
||||
char *p = strchr(pdup, '=');
|
||||
if (p == NULL) {
|
||||
if (p == nullptr) {
|
||||
printf("Please specify parameter as NAME=VALUE");
|
||||
exit(1);
|
||||
}
|
||||
float value = strtof(p+1, NULL);
|
||||
float value = strtof(p+1, nullptr);
|
||||
*p = 0;
|
||||
enum ap_var_type var_type;
|
||||
AP_Param *vp = AP_Param::find(pdup, &var_type);
|
||||
if (vp == NULL) {
|
||||
if (vp == nullptr) {
|
||||
printf("Unknown parameter %s\n", pdup);
|
||||
exit(1);
|
||||
}
|
||||
@ -85,7 +85,7 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||
#endif
|
||||
_optical_flow = (OpticalFlow *)AP_Param::find_object("FLOW");
|
||||
|
||||
if (_sitl != NULL) {
|
||||
if (_sitl != nullptr) {
|
||||
// setup some initial values
|
||||
#ifndef HIL_MODE
|
||||
_update_barometer(100);
|
||||
@ -137,7 +137,7 @@ void SITL_State::_fdm_input_step(void)
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if (_scheduler->interrupts_are_blocked() || _sitl == NULL) {
|
||||
if (_scheduler->interrupts_are_blocked() || _sitl == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -149,7 +149,7 @@ void SITL_State::_fdm_input_step(void)
|
||||
|
||||
_scheduler->sitl_begin_atomic();
|
||||
|
||||
if (_update_count == 0 && _sitl != NULL) {
|
||||
if (_update_count == 0 && _sitl != nullptr) {
|
||||
_update_gps(0, 0, 0, 0, 0, 0, false);
|
||||
_update_barometer(0);
|
||||
_scheduler->timer_event();
|
||||
@ -157,7 +157,7 @@ void SITL_State::_fdm_input_step(void)
|
||||
return;
|
||||
}
|
||||
|
||||
if (_sitl != NULL) {
|
||||
if (_sitl != nullptr) {
|
||||
_update_gps(_sitl->state.latitude, _sitl->state.longitude,
|
||||
_sitl->state.altitude,
|
||||
_sitl->state.speedN, _sitl->state.speedE, _sitl->state.speedD,
|
||||
@ -288,10 +288,10 @@ void SITL_State::_fdm_input_local(void)
|
||||
}
|
||||
}
|
||||
|
||||
if (gimbal != NULL) {
|
||||
if (gimbal != nullptr) {
|
||||
gimbal->update();
|
||||
}
|
||||
if (adsb != NULL) {
|
||||
if (adsb != nullptr) {
|
||||
adsb->update();
|
||||
}
|
||||
|
||||
|
@ -113,8 +113,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
int opt;
|
||||
// default to CMAC
|
||||
const char *home_str = "-35.363261,149.165230,584,353";
|
||||
const char *model_str = NULL;
|
||||
char *autotest_dir = NULL;
|
||||
const char *model_str = nullptr;
|
||||
char *autotest_dir = nullptr;
|
||||
float speedup = 1.0f;
|
||||
|
||||
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
|
||||
@ -131,7 +131,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
_rcout_port = 5502;
|
||||
_simin_port = 5501;
|
||||
_fdm_address = "127.0.0.1";
|
||||
_client_address = NULL;
|
||||
_client_address = nullptr;
|
||||
_instance = 0;
|
||||
|
||||
enum long_options {
|
||||
@ -211,7 +211,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
model_str = gopt.optarg;
|
||||
break;
|
||||
case 's':
|
||||
speedup = strtof(gopt.optarg, NULL);
|
||||
speedup = strtof(gopt.optarg, nullptr);
|
||||
break;
|
||||
case 'F':
|
||||
_fdm_address = gopt.optarg;
|
||||
|
@ -13,15 +13,15 @@ using namespace HALSITL;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
AP_HAL::Proc Scheduler::_failsafe = NULL;
|
||||
AP_HAL::Proc Scheduler::_failsafe = nullptr;
|
||||
volatile bool Scheduler::_timer_suspended = false;
|
||||
volatile bool Scheduler::_timer_event_missed = false;
|
||||
|
||||
AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
||||
AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
|
||||
uint8_t Scheduler::_num_timer_procs = 0;
|
||||
bool Scheduler::_in_timer_proc = false;
|
||||
|
||||
AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
||||
AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
|
||||
uint8_t Scheduler::_num_io_procs = 0;
|
||||
bool Scheduler::_in_io_proc = false;
|
||||
|
||||
@ -129,7 +129,7 @@ void Scheduler::system_initialized() {
|
||||
// i386 with gcc doesn't work with FE_INVALID
|
||||
exceptions |= FE_INVALID;
|
||||
#endif
|
||||
if (_sitlState->_sitl == NULL || _sitlState->_sitl->float_exception) {
|
||||
if (_sitlState->_sitl == nullptr || _sitlState->_sitl->float_exception) {
|
||||
feenableexcept(exceptions);
|
||||
} else {
|
||||
feclearexcept(exceptions);
|
||||
@ -162,7 +162,7 @@ void Scheduler::_run_timer_procs(bool called_from_isr)
|
||||
// need be. We assume the failsafe code can't
|
||||
// block. If it does then we will recurse and die when
|
||||
// we run out of stack
|
||||
if (_failsafe != NULL) {
|
||||
if (_failsafe != nullptr) {
|
||||
_failsafe();
|
||||
}
|
||||
return;
|
||||
@ -181,7 +181,7 @@ void Scheduler::_run_timer_procs(bool called_from_isr)
|
||||
}
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
if (_failsafe != nullptr) {
|
||||
_failsafe();
|
||||
}
|
||||
|
||||
|
@ -9,7 +9,7 @@
|
||||
class HALSITL::Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
pthread_mutex_init(&_lock, nullptr);
|
||||
}
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
|
@ -67,17 +67,17 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
tcpclient:192.168.2.15:5762
|
||||
uart:/dev/ttyUSB0:57600
|
||||
*/
|
||||
char *saveptr = NULL;
|
||||
char *saveptr = nullptr;
|
||||
char *s = strdup(path);
|
||||
char *devtype = strtok_r(s, ":", &saveptr);
|
||||
char *args1 = strtok_r(NULL, ":", &saveptr);
|
||||
char *args2 = strtok_r(NULL, ":", &saveptr);
|
||||
char *args1 = strtok_r(nullptr, ":", &saveptr);
|
||||
char *args2 = strtok_r(nullptr, ":", &saveptr);
|
||||
if (strcmp(devtype, "tcp") == 0) {
|
||||
uint16_t port = atoi(args1);
|
||||
bool wait = (args2 && strcmp(args2, "wait") == 0);
|
||||
_tcp_start_connection(port, wait);
|
||||
} else if (strcmp(devtype, "tcpclient") == 0) {
|
||||
if (args2 == NULL) {
|
||||
if (args2 == nullptr) {
|
||||
AP_HAL::panic("Invalid tcp client path: %s", path);
|
||||
}
|
||||
uint16_t port = atoi(args2);
|
||||
@ -234,7 +234,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
if (wait_for_connection) {
|
||||
fprintf(stdout, "Waiting for connection ....\n");
|
||||
fflush(stdout);
|
||||
_fd = accept(_listen_fd, NULL, NULL);
|
||||
_fd = accept(_listen_fd, nullptr, nullptr);
|
||||
if (_fd == -1) {
|
||||
fprintf(stderr, "accept() error - %s", strerror(errno));
|
||||
exit(1);
|
||||
@ -353,7 +353,7 @@ void UARTDriver::_check_connection(void)
|
||||
return;
|
||||
}
|
||||
if (_select_check(_listen_fd)) {
|
||||
_fd = accept(_listen_fd, NULL, NULL);
|
||||
_fd = accept(_listen_fd, nullptr, nullptr);
|
||||
if (_fd != -1) {
|
||||
int one = 1;
|
||||
_connected = true;
|
||||
@ -382,7 +382,7 @@ bool UARTDriver::_select_check(int fd)
|
||||
tv.tv_sec = 0;
|
||||
tv.tv_usec = 0;
|
||||
|
||||
if (select(fd+1, &fds, NULL, NULL, &tv) == 1) {
|
||||
if (select(fd+1, &fds, nullptr, nullptr, &tv) == 1) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -33,7 +33,7 @@ void SITL_State::_update_barometer(float altitude)
|
||||
|
||||
float sim_alt = altitude;
|
||||
|
||||
if (_barometer == NULL) {
|
||||
if (_barometer == nullptr) {
|
||||
// this sketch doesn't use a barometer
|
||||
return;
|
||||
}
|
||||
|
@ -30,7 +30,7 @@ void SITL_State::_update_compass(float rollDeg, float pitchDeg, float yawDeg)
|
||||
{
|
||||
static uint32_t last_update;
|
||||
|
||||
if (_compass == NULL) {
|
||||
if (_compass == nullptr) {
|
||||
// no compass in this sketch
|
||||
return;
|
||||
}
|
||||
|
@ -134,7 +134,7 @@ static void simulation_timeval(struct timeval *tv)
|
||||
static struct timeval first_tv;
|
||||
if (first_usec == 0) {
|
||||
first_usec = now;
|
||||
gettimeofday(&first_tv, NULL);
|
||||
gettimeofday(&first_tv, nullptr);
|
||||
}
|
||||
*tv = first_tv;
|
||||
tv->tv_sec += now / 1000000ULL;
|
||||
@ -522,7 +522,7 @@ uint16_t SITL_State::_gps_nmea_checksum(const char *s)
|
||||
*/
|
||||
void SITL_State::_gps_nmea_printf(const char *fmt, ...)
|
||||
{
|
||||
char *s = NULL;
|
||||
char *s = nullptr;
|
||||
uint16_t csum;
|
||||
char trailer[6];
|
||||
|
||||
|
@ -154,7 +154,7 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
||||
double xAccel, double yAccel, double zAccel, // Local to plane
|
||||
float airspeed, float altitude)
|
||||
{
|
||||
if (_ins == NULL) {
|
||||
if (_ins == nullptr) {
|
||||
// no inertial sensor in this sketch
|
||||
return;
|
||||
}
|
||||
|
@ -18,7 +18,7 @@ static struct {
|
||||
|
||||
void init()
|
||||
{
|
||||
gettimeofday(&state.start_time, NULL);
|
||||
gettimeofday(&state.start_time, nullptr);
|
||||
}
|
||||
|
||||
void panic(const char *errormsg, ...)
|
||||
@ -52,7 +52,7 @@ uint64_t micros64()
|
||||
}
|
||||
|
||||
struct timeval tp;
|
||||
gettimeofday(&tp, NULL);
|
||||
gettimeofday(&tp, nullptr);
|
||||
uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) -
|
||||
(state.start_time.tv_sec +
|
||||
(state.start_time.tv_usec * 1.0e-6)));
|
||||
@ -68,7 +68,7 @@ uint64_t millis64()
|
||||
}
|
||||
|
||||
struct timeval tp;
|
||||
gettimeofday(&tp, NULL);
|
||||
gettimeofday(&tp, nullptr);
|
||||
uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) -
|
||||
(state.start_time.tv_sec +
|
||||
(state.start_time.tv_usec*1.0e-6)));
|
||||
|
@ -248,7 +248,7 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
struct adc_msg_s buf_adc[VRBRAIN_ANALOG_MAX_CHANNELS];
|
||||
|
||||
// cope with initial setup of stop pin
|
||||
if (_channels[_current_stop_pin_i] == NULL ||
|
||||
if (_channels[_current_stop_pin_i] == nullptr ||
|
||||
_channels[_current_stop_pin_i]->_stop_pin == -1) {
|
||||
next_stop_pin();
|
||||
}
|
||||
@ -263,7 +263,7 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
(unsigned)buf_adc[i].am_data);
|
||||
for (uint8_t j=0; j<VRBRAIN_ANALOG_MAX_CHANNELS; j++) {
|
||||
VRBRAIN::VRBRAINAnalogSource *c = _channels[j];
|
||||
if (c != NULL && buf_adc[i].am_channel == c->_pin) {
|
||||
if (c != nullptr && buf_adc[i].am_channel == c->_pin) {
|
||||
// add a value if either there is no stop pin, or
|
||||
// the stop pin has been settling for enough time
|
||||
if (c->_stop_pin == -1 ||
|
||||
@ -284,13 +284,13 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
AP_HAL::AnalogSource* VRBRAINAnalogIn::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j=0; j<VRBRAIN_ANALOG_MAX_CHANNELS; j++) {
|
||||
if (_channels[j] == NULL) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new VRBRAINAnalogSource(pin, 0.0f);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
hal.console->println("Out of analog channels");
|
||||
return NULL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -126,7 +126,7 @@ HAL_VRBRAIN::HAL_VRBRAIN() :
|
||||
&rcoutDriver, /* rcoutput */
|
||||
&schedulerInstance, /* scheduler */
|
||||
&utilInstance, /* util */
|
||||
NULL) /* no onboard optical flow */
|
||||
nullptr) /* no onboard optical flow */
|
||||
{}
|
||||
|
||||
bool _vrbrain_thread_should_exit = false; /**< Daemon exit flag */
|
||||
@ -205,7 +205,7 @@ static int main_loop(int argc, char **argv)
|
||||
will only ever be called if a loop() call runs for more than
|
||||
0.1 second
|
||||
*/
|
||||
hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL);
|
||||
hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr);
|
||||
|
||||
g_callbacks->loop();
|
||||
|
||||
@ -283,7 +283,7 @@ void HAL_VRBRAIN::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
APM_MAIN_PRIORITY,
|
||||
APM_MAIN_THREAD_STACK_SIZE,
|
||||
main_loop,
|
||||
NULL);
|
||||
nullptr);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -31,7 +31,7 @@ void NSHShellStream::shell_thread(void *arg)
|
||||
dup2(nsh->child.out, 1);
|
||||
dup2(nsh->child.out, 2);
|
||||
|
||||
nsh_consolemain(0, NULL);
|
||||
nsh_consolemain(0, nullptr);
|
||||
|
||||
nsh->shell_stdin = -1;
|
||||
nsh->shell_stdout = -1;
|
||||
|
@ -20,7 +20,7 @@ void VRBRAINRCInput::init()
|
||||
AP_HAL::panic("Unable to subscribe to input_rc");
|
||||
}
|
||||
clear_overrides();
|
||||
pthread_mutex_init(&rcin_mutex, NULL);
|
||||
pthread_mutex_init(&rcin_mutex, nullptr);
|
||||
}
|
||||
|
||||
bool VRBRAINRCInput::new_input()
|
||||
|
@ -67,10 +67,10 @@ void VRBRAINRCOutput::init()
|
||||
}
|
||||
|
||||
// publish actuator vaules on demand
|
||||
_actuator_direct_pub = NULL;
|
||||
_actuator_direct_pub = nullptr;
|
||||
|
||||
// and armed state
|
||||
_actuator_armed_pub = NULL;
|
||||
_actuator_armed_pub = nullptr;
|
||||
}
|
||||
|
||||
|
||||
@ -390,7 +390,7 @@ void VRBRAINRCOutput::_arm_actuators(bool arm)
|
||||
_armed.lockdown = false;
|
||||
_armed.force_failsafe = false;
|
||||
|
||||
if (_actuator_armed_pub == NULL) {
|
||||
if (_actuator_armed_pub == nullptr) {
|
||||
_actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed);
|
||||
@ -432,7 +432,7 @@ void VRBRAINRCOutput::_publish_actuators(void)
|
||||
actuators.values[i] = actuators.values[i]*2 - 1;
|
||||
}
|
||||
|
||||
if (_actuator_direct_pub == NULL) {
|
||||
if (_actuator_direct_pub == nullptr) {
|
||||
_actuator_direct_pub = orb_advertise(ORB_ID(actuator_direct), &actuators);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_direct), _actuator_direct_pub, &actuators);
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user