clang-tidy modernize-use-nullptr

This commit is contained in:
Daniel Agar
2017-01-28 20:21:58 -05:00
parent ec2467d4a5
commit e927f3e040
48 changed files with 155 additions and 153 deletions
+4 -2
View File
@@ -1,5 +1,7 @@
Checks: '-*,readability-braces-around-statements' Checks: '-*,readability-braces-around-statements,
WarningsAsErrors: readability-braces-around-statements modernize-use-nullptr'
WarningsAsErrors: 'readability-braces-around-statements,
modernize-use-nullptr'
HeaderFilterRegex: '*.h, *.hpp' HeaderFilterRegex: '*.h, *.hpp'
AnalyzeTemporaryDtors: false AnalyzeTemporaryDtors: false
CheckOptions: CheckOptions:
+3 -3
View File
@@ -86,7 +86,7 @@ void
RingBuffer::flush() RingBuffer::flush()
{ {
while (!empty()) { while (!empty()) {
get(NULL); get(nullptr);
} }
} }
@@ -179,7 +179,7 @@ RingBuffer::force(const void *val, size_t val_size)
break; break;
} }
get(NULL); get(nullptr);
overwrote = true; overwrote = true;
} }
@@ -281,7 +281,7 @@ RingBuffer::get(void *val, size_t val_size)
next = _next(candidate); next = _next(candidate);
/* go ahead and read from this index */ /* go ahead and read from this index */
if (val != NULL) { if (val != nullptr) {
memcpy(val, &_buf[candidate * _item_size], val_size); memcpy(val, &_buf[candidate * _item_size], val_size);
} }
+8 -8
View File
@@ -139,7 +139,7 @@ VDev::register_driver(const char *name, void *data)
PX4_DEBUG("VDev::register_driver %s", name); PX4_DEBUG("VDev::register_driver %s", name);
int ret = -ENOSPC; int ret = -ENOSPC;
if (name == NULL || data == NULL) { if (name == nullptr || data == nullptr) {
return -EINVAL; return -EINVAL;
} }
@@ -156,7 +156,7 @@ VDev::register_driver(const char *name, void *data)
} }
for (int i = 0; i < PX4_MAX_DEV; ++i) { for (int i = 0; i < PX4_MAX_DEV; ++i) {
if (devmap[i] == NULL) { if (devmap[i] == nullptr) {
devmap[i] = new px4_dev_t(name, (void *)data); devmap[i] = new px4_dev_t(name, (void *)data);
PX4_DEBUG("Registered DEV %s", name); PX4_DEBUG("Registered DEV %s", name);
ret = PX4_OK; ret = PX4_OK;
@@ -179,7 +179,7 @@ VDev::unregister_driver(const char *name)
PX4_DEBUG("VDev::unregister_driver %s", name); PX4_DEBUG("VDev::unregister_driver %s", name);
int ret = -EINVAL; int ret = -EINVAL;
if (name == NULL) { if (name == nullptr) {
return -EINVAL; return -EINVAL;
} }
@@ -188,7 +188,7 @@ VDev::unregister_driver(const char *name)
for (int i = 0; i < PX4_MAX_DEV; ++i) { for (int i = 0; i < PX4_MAX_DEV; ++i) {
if (devmap[i] && (strcmp(name, devmap[i]->name) == 0)) { if (devmap[i] && (strcmp(name, devmap[i]->name) == 0)) {
delete devmap[i]; delete devmap[i];
devmap[i] = NULL; devmap[i] = nullptr;
PX4_DEBUG("Unregistered DEV %s", name); PX4_DEBUG("Unregistered DEV %s", name);
ret = PX4_OK; ret = PX4_OK;
break; break;
@@ -213,7 +213,7 @@ VDev::unregister_class_devname(const char *class_devname, unsigned class_instanc
if (devmap[i] && strcmp(devmap[i]->name, name) == 0) { if (devmap[i] && strcmp(devmap[i]->name, name) == 0) {
delete devmap[i]; delete devmap[i];
PX4_DEBUG("Unregistered class DEV %s", name); PX4_DEBUG("Unregistered class DEV %s", name);
devmap[i] = NULL; devmap[i] = nullptr;
pthread_mutex_unlock(&devmutex); pthread_mutex_unlock(&devmutex);
return PX4_OK; return PX4_OK;
} }
@@ -551,7 +551,7 @@ VDev *VDev::getDev(const char *path)
pthread_mutex_unlock(&devmutex); pthread_mutex_unlock(&devmutex);
return NULL; return nullptr;
} }
void VDev::showDevices() void VDev::showDevices()
@@ -628,7 +628,7 @@ const char *VDev::topicList(unsigned int *next)
} }
} }
return NULL; return nullptr;
} }
const char *VDev::devList(unsigned int *next) const char *VDev::devList(unsigned int *next)
@@ -639,7 +639,7 @@ const char *VDev::devList(unsigned int *next)
} }
} }
return NULL; return nullptr;
} }
} // namespace device } // namespace device
+4 -4
View File
@@ -67,7 +67,7 @@ extern "C" {
inline bool valid_fd(int fd) inline bool valid_fd(int fd)
{ {
pthread_mutex_lock(&filemutex); pthread_mutex_lock(&filemutex);
bool ret = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != NULL); bool ret = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != nullptr);
pthread_mutex_unlock(&filemutex); pthread_mutex_unlock(&filemutex);
return ret; return ret;
} }
@@ -75,7 +75,7 @@ extern "C" {
inline VDev *get_vdev(int fd) inline VDev *get_vdev(int fd)
{ {
pthread_mutex_lock(&filemutex); pthread_mutex_lock(&filemutex);
bool valid = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != NULL); bool valid = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != nullptr);
VDev *dev; VDev *dev;
if (valid) { if (valid) {
@@ -115,7 +115,7 @@ extern "C" {
pthread_mutex_lock(&filemutex); pthread_mutex_lock(&filemutex);
for (i = 0; i < PX4_MAX_FD; ++i) { for (i = 0; i < PX4_MAX_FD; ++i) {
if (filemap[i] == 0) { if (filemap[i] == nullptr) {
filemap[i] = new device::file_t(flags, dev, i); filemap[i] = new device::file_t(flags, dev, i);
break; break;
} }
@@ -290,7 +290,7 @@ extern "C" {
for (i = 0; i < nfds; ++i) { for (i = 0; i < nfds; ++i) {
fds[i].sem = &sem; fds[i].sem = &sem;
fds[i].revents = 0; fds[i].revents = 0;
fds[i].priv = NULL; fds[i].priv = nullptr;
VDev *dev = get_vdev(fds[i].fd); VDev *dev = get_vdev(fds[i].fd);
+1 -1
View File
@@ -320,7 +320,7 @@ int GPS::init()
{ {
char gps_num[2] = {(char)('0' + _gps_num), 0}; char gps_num[2] = {(char)('0' + _gps_num), 0};
char *const args[2] = { gps_num, NULL }; char *const args[2] = { gps_num, nullptr };
/* start the GPS driver worker task */ /* start the GPS driver worker task */
_task = px4_task_spawn_cmd("gps", SCHED_DEFAULT, _task = px4_task_spawn_cmd("gps", SCHED_DEFAULT,
+6 -6
View File
@@ -191,7 +191,7 @@ PWMSim::PWMSim() :
_poll_fds{}, _poll_fds{},
_poll_fds_num(0), _poll_fds_num(0),
_armed_sub(-1), _armed_sub(-1),
_outputs_pub(0), _outputs_pub(nullptr),
_num_outputs(0), _num_outputs(0),
_primary_pwm_device(false), _primary_pwm_device(false),
_groups_required(0), _groups_required(0),
@@ -487,7 +487,7 @@ PWMSim::task_main()
} }
/* do mixing */ /* do mixing */
num_outputs = _mixers->mix(&outputs.output[0], num_outputs, NULL); num_outputs = _mixers->mix(&outputs.output[0], num_outputs, nullptr);
outputs.noutputs = num_outputs; outputs.noutputs = num_outputs;
outputs.timestamp = hrt_absolute_time(); outputs.timestamp = hrt_absolute_time();
@@ -957,13 +957,13 @@ fake(int argc, char *argv[])
actuator_controls_s ac; actuator_controls_s ac;
ac.control[0] = strtol(argv[1], 0, 0) / 100.0f; ac.control[0] = strtol(argv[1], nullptr, 0) / 100.0f;
ac.control[1] = strtol(argv[2], 0, 0) / 100.0f; ac.control[1] = strtol(argv[2], nullptr, 0) / 100.0f;
ac.control[2] = strtol(argv[3], 0, 0) / 100.0f; ac.control[2] = strtol(argv[3], nullptr, 0) / 100.0f;
ac.control[3] = strtol(argv[4], 0, 0) / 100.0f; ac.control[3] = strtol(argv[4], nullptr, 0) / 100.0f;
orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac); orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac);
+1 -1
View File
@@ -161,7 +161,7 @@ static int vmount_thread_main(int argc, char *argv[])
for (int i = 0 ; i < 3; ++i) { for (int i = 0 ; i < 3; ++i) {
if (!strcmp(argv[1], axis_names[i])) { if (!strcmp(argv[1], axis_names[i])) {
long angle_deg = strtol(argv[2], NULL, 0); long angle_deg = strtol(argv[2], nullptr, 0);
angles[i] = (float)angle_deg; angles[i] = (float)angle_deg;
found_axis = true; found_axis = true;
} }
@@ -177,7 +177,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
7000, 7000,
attitude_estimator_ekf_thread_main, attitude_estimator_ekf_thread_main,
(argv) ? (char * const *)&argv[2] : (char * const *)NULL); (argv) ? (char * const *)&argv[2] : (char * const *)nullptr);
return 0; return 0;
} }
@@ -121,7 +121,7 @@ AttitudePositionEstimatorEKF *g_estimator = nullptr;
} }
AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() : AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() :
SuperBlock(NULL, "PE"), SuperBlock(nullptr, "PE"),
_task_should_exit(false), _task_should_exit(false),
_task_running(false), _task_running(false),
_estimator_task(-1), _estimator_task(-1),
@@ -396,7 +396,7 @@ int AttitudePositionEstimatorEKF::check_filter_state()
int check = _ekf->CheckAndBound(&ekf_report); int check = _ekf->CheckAndBound(&ekf_report);
const char *const feedback[] = { 0, const char *const feedback[] = { nullptr,
"NaN in states, resetting", "NaN in states, resetting",
"stale sensor data, resetting", "stale sensor data, resetting",
"got initial position lock", "got initial position lock",
@@ -1721,7 +1721,7 @@ int ekf_att_pos_estimator_main(int argc, char *argv[])
} }
if (!strcmp(argv[1], "debug")) { if (!strcmp(argv[1], "debug")) {
int debug = strtoul(argv[2], NULL, 10); int debug = strtoul(argv[2], nullptr, 10);
int ret = estimator::g_estimator->set_debuglevel(debug); int ret = estimator::g_estimator->set_debuglevel(debug);
return ret; return ret;
+1 -1
View File
@@ -462,7 +462,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 20, SCHED_PRIORITY_MAX - 20,
2048, 2048,
fixedwing_control_thread_main, fixedwing_control_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL); (argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
thread_running = true; thread_running = true;
exit(0); exit(0);
} }
@@ -74,7 +74,7 @@ int mc_att_control_m_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
1900, 1900,
mc_att_control_start_main, mc_att_control_start_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL); (argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
return 0; return 0;
} }
@@ -75,7 +75,7 @@ int mc_pos_control_m_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
2500, 2500,
mc_pos_control_start_main, mc_pos_control_start_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL); (argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
return 0; return 0;
} }
+9 -9
View File
@@ -57,14 +57,14 @@ Block::Block(SuperBlock *parent, const char *name) :
_subscriptions(), _subscriptions(),
_params() _params()
{ {
if (getParent() != NULL) { if (getParent() != nullptr) {
getParent()->getChildren().add(this); getParent()->getChildren().add(this);
} }
} }
void Block::getName(char *buf, size_t n) void Block::getName(char *buf, size_t n)
{ {
if (getParent() == NULL) { if (getParent() == nullptr) {
strncpy(buf, _name, n); strncpy(buf, _name, n);
// ensure string is terminated // ensure string is terminated
buf[n - 1] = '\0'; buf[n - 1] = '\0';
@@ -89,7 +89,7 @@ void Block::updateParams()
BlockParamBase *param = getParams().getHead(); BlockParamBase *param = getParams().getHead();
int count = 0; int count = 0;
while (param != NULL) { while (param != nullptr) {
if (count++ > maxParamsPerBlock) { if (count++ > maxParamsPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -108,7 +108,7 @@ void Block::updateSubscriptions()
uORB::SubscriptionNode *sub = getSubscriptions().getHead(); uORB::SubscriptionNode *sub = getSubscriptions().getHead();
int count = 0; int count = 0;
while (sub != NULL) { while (sub != nullptr) {
if (count++ > maxSubscriptionsPerBlock) { if (count++ > maxSubscriptionsPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -126,7 +126,7 @@ void Block::updatePublications()
uORB::PublicationNode *pub = getPublications().getHead(); uORB::PublicationNode *pub = getPublications().getHead();
int count = 0; int count = 0;
while (pub != NULL) { while (pub != nullptr) {
if (count++ > maxPublicationsPerBlock) { if (count++ > maxPublicationsPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -145,7 +145,7 @@ void SuperBlock::setDt(float dt)
Block *child = getChildren().getHead(); Block *child = getChildren().getHead();
int count = 0; int count = 0;
while (child != NULL) { while (child != nullptr) {
if (count++ > maxChildrenPerBlock) { if (count++ > maxChildrenPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -163,7 +163,7 @@ void SuperBlock::updateChildParams()
Block *child = getChildren().getHead(); Block *child = getChildren().getHead();
int count = 0; int count = 0;
while (child != NULL) { while (child != nullptr) {
if (count++ > maxChildrenPerBlock) { if (count++ > maxChildrenPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -181,7 +181,7 @@ void SuperBlock::updateChildSubscriptions()
Block *child = getChildren().getHead(); Block *child = getChildren().getHead();
int count = 0; int count = 0;
while (child != NULL) { while (child != nullptr) {
if (count++ > maxChildrenPerBlock) { if (count++ > maxChildrenPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
@@ -199,7 +199,7 @@ void SuperBlock::updateChildPublications()
Block *child = getChildren().getHead(); Block *child = getChildren().getHead();
int count = 0; int count = 0;
while (child != NULL) { while (child != nullptr) {
if (count++ > maxChildrenPerBlock) { if (count++ > maxChildrenPerBlock) {
char name[blockNameLengthMax]; char name[blockNameLengthMax];
getName(name, blockNameLengthMax); getName(name, blockNameLengthMax);
+1 -1
View File
@@ -53,7 +53,7 @@ BlockParamBase::BlockParamBase(Block *parent, const char *name, bool parent_pref
{ {
char fullname[blockNameLengthMax]; char fullname[blockNameLengthMax];
if (parent == NULL) { if (parent == nullptr) {
strncpy(fullname, name, blockNameLengthMax); strncpy(fullname, name, blockNameLengthMax);
} else { } else {
+1 -1
View File
@@ -45,7 +45,7 @@ namespace launchdetection
{ {
LaunchDetector::LaunchDetector() : LaunchDetector::LaunchDetector() :
SuperBlock(NULL, "LAUN"), SuperBlock(nullptr, "LAUN"),
activeLaunchDetectionMethodIndex(-1), activeLaunchDetectionMethodIndex(-1),
launchdetection_on(this, "ALL_ON"), launchdetection_on(this, "ALL_ON"),
throttlePreTakeoff(nullptr, "FW_THR_IDLE") throttlePreTakeoff(nullptr, "FW_THR_IDLE")
+1 -1
View File
@@ -52,7 +52,7 @@ namespace runwaytakeoff
{ {
RunwayTakeoff::RunwayTakeoff() : RunwayTakeoff::RunwayTakeoff() :
SuperBlock(NULL, "RWTO"), SuperBlock(nullptr, "RWTO"),
_state(), _state(),
_initialized(false), _initialized(false),
_initialized_time(0), _initialized_time(0),
+4 -4
View File
@@ -157,7 +157,7 @@ static constexpr uint8_t COMMANDER_MAX_GPS_NOISE = 60; /**< Maximum percentage
#define HIL_ID_MAX 1999 #define HIL_ID_MAX 1999
/* Mavlink log uORB handle */ /* Mavlink log uORB handle */
static orb_advert_t mavlink_log_pub = 0; static orb_advert_t mavlink_log_pub = nullptr;
/* System autostart ID */ /* System autostart ID */
static int autostart_id; static int autostart_id;
@@ -1714,7 +1714,7 @@ int commander_thread_main(int argc, char *argv[])
(void)pthread_attr_setschedparam(&commander_low_prio_attr, &param); (void)pthread_attr_setschedparam(&commander_low_prio_attr, &param);
#endif #endif
pthread_create(&commander_low_prio_thread, &commander_low_prio_attr, commander_low_prio_loop, NULL); pthread_create(&commander_low_prio_thread, &commander_low_prio_attr, commander_low_prio_loop, nullptr);
pthread_attr_destroy(&commander_low_prio_attr); pthread_attr_destroy(&commander_low_prio_attr);
while (!thread_should_exit) { while (!thread_should_exit) {
@@ -3075,7 +3075,7 @@ int commander_thread_main(int argc, char *argv[])
} }
/* wait for threads to complete */ /* wait for threads to complete */
ret = pthread_join(commander_low_prio_thread, NULL); ret = pthread_join(commander_low_prio_thread, nullptr);
if (ret) { if (ret) {
warn("join failed: %d", ret); warn("join failed: %d", ret);
@@ -4169,5 +4169,5 @@ void *commander_low_prio_loop(void *arg)
px4_close(cmd_sub); px4_close(cmd_sub);
return NULL; return nullptr;
} }
+4 -4
View File
@@ -548,9 +548,9 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
worker_data.sub_mag[cur_mag] = -1; worker_data.sub_mag[cur_mag] = -1;
// Initialize to no memory allocated // Initialize to no memory allocated
worker_data.x[cur_mag] = NULL; worker_data.x[cur_mag] = nullptr;
worker_data.y[cur_mag] = NULL; worker_data.y[cur_mag] = nullptr;
worker_data.z[cur_mag] = NULL; worker_data.z[cur_mag] = nullptr;
worker_data.calibration_counter_total[cur_mag] = 0; worker_data.calibration_counter_total[cur_mag] = 0;
} }
@@ -563,7 +563,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) { if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) {
calibration_log_critical(mavlink_log_pub, "[cal] ERROR: out of memory"); calibration_log_critical(mavlink_log_pub, "[cal] ERROR: out of memory");
result = calibrate_return_error; result = calibrate_return_error;
} }
@@ -564,7 +564,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta
for (;;) { for (;;) {
devname = px4_get_device_names(&handle); devname = px4_get_device_names(&handle);
if (devname == NULL) { if (devname == nullptr) {
break; break;
} }
@@ -94,7 +94,7 @@ int basicBlocksTest()
int blockLimitTest() int blockLimitTest()
{ {
printf("Test BlockLimit\t\t\t: "); printf("Test BlockLimit\t\t\t: ");
BlockLimit limit(NULL, "TEST"); BlockLimit limit(nullptr, "TEST");
// initial state // initial state
ASSERT_CL(equal(1.0f, limit.getMax())); ASSERT_CL(equal(1.0f, limit.getMax()));
ASSERT_CL(equal(-1.0f, limit.getMin())); ASSERT_CL(equal(-1.0f, limit.getMin()));
@@ -110,7 +110,7 @@ int blockLimitTest()
int blockLimitSymTest() int blockLimitSymTest()
{ {
printf("Test BlockLimitSym\t\t: "); printf("Test BlockLimitSym\t\t: ");
BlockLimitSym limit(NULL, "TEST"); BlockLimitSym limit(nullptr, "TEST");
// initial state // initial state
ASSERT_CL(equal(1.0f, limit.getMax())); ASSERT_CL(equal(1.0f, limit.getMax()));
ASSERT_CL(equal(0.0f, limit.getDt())); ASSERT_CL(equal(0.0f, limit.getDt()));
@@ -125,7 +125,7 @@ int blockLimitSymTest()
int blockLowPassTest() int blockLowPassTest()
{ {
printf("Test BlockLowPass\t\t: "); printf("Test BlockLowPass\t\t: ");
BlockLowPass lowPass(NULL, "TEST_LP"); BlockLowPass lowPass(nullptr, "TEST_LP");
// test initial state // test initial state
ASSERT_CL(equal(10.0f, lowPass.getFCut())); ASSERT_CL(equal(10.0f, lowPass.getFCut()));
ASSERT_CL(equal(0.0f, lowPass.getState())); ASSERT_CL(equal(0.0f, lowPass.getState()));
@@ -153,7 +153,7 @@ int blockLowPassTest()
int blockHighPassTest() int blockHighPassTest()
{ {
printf("Test BlockHighPass\t\t: "); printf("Test BlockHighPass\t\t: ");
BlockHighPass highPass(NULL, "TEST_HP"); BlockHighPass highPass(nullptr, "TEST_HP");
// test initial state // test initial state
ASSERT_CL(equal(10.0f, highPass.getFCut())); ASSERT_CL(equal(10.0f, highPass.getFCut()));
ASSERT_CL(equal(0.0f, highPass.getU())); ASSERT_CL(equal(0.0f, highPass.getU()));
@@ -184,7 +184,7 @@ int blockHighPassTest()
int blockLowPass2Test() int blockLowPass2Test()
{ {
printf("Test BlockLowPass2\t\t: "); printf("Test BlockLowPass2\t\t: ");
BlockLowPass2 lowPass(NULL, "TEST_LP", 100); BlockLowPass2 lowPass(nullptr, "TEST_LP", 100);
// test initial state // test initial state
ASSERT_CL(equal(10.0f, lowPass.getFCutParam())); ASSERT_CL(equal(10.0f, lowPass.getFCutParam()));
ASSERT_CL(equal(0.0f, lowPass.getState())); ASSERT_CL(equal(0.0f, lowPass.getState()));
@@ -212,7 +212,7 @@ int blockLowPass2Test()
int blockIntegralTest() int blockIntegralTest()
{ {
printf("Test BlockIntegral\t\t: "); printf("Test BlockIntegral\t\t: ");
BlockIntegral integral(NULL, "TEST_I"); BlockIntegral integral(nullptr, "TEST_I");
// test initial state // test initial state
ASSERT_CL(equal(1.0f, integral.getMax())); ASSERT_CL(equal(1.0f, integral.getMax()));
ASSERT_CL(equal(0.0f, integral.getDt())); ASSERT_CL(equal(0.0f, integral.getDt()));
@@ -249,7 +249,7 @@ int blockIntegralTest()
int blockIntegralTrapTest() int blockIntegralTrapTest()
{ {
printf("Test BlockIntegralTrap\t\t: "); printf("Test BlockIntegralTrap\t\t: ");
BlockIntegralTrap integral(NULL, "TEST_I"); BlockIntegralTrap integral(nullptr, "TEST_I");
// test initial state // test initial state
ASSERT_CL(equal(1.0f, integral.getMax())); ASSERT_CL(equal(1.0f, integral.getMax()));
ASSERT_CL(equal(0.0f, integral.getDt())); ASSERT_CL(equal(0.0f, integral.getDt()));
@@ -292,7 +292,7 @@ int blockIntegralTrapTest()
int blockDerivativeTest() int blockDerivativeTest()
{ {
printf("Test BlockDerivative\t\t: "); printf("Test BlockDerivative\t\t: ");
BlockDerivative derivative(NULL, "TEST_D"); BlockDerivative derivative(nullptr, "TEST_D");
// test initial state // test initial state
ASSERT_CL(equal(0.0f, derivative.getU())); ASSERT_CL(equal(0.0f, derivative.getU()));
ASSERT_CL(equal(10.0f, derivative.getLP())); ASSERT_CL(equal(10.0f, derivative.getLP()));
@@ -315,7 +315,7 @@ int blockDerivativeTest()
int blockPTest() int blockPTest()
{ {
printf("Test BlockP\t\t\t: "); printf("Test BlockP\t\t\t: ");
BlockP blockP(NULL, "TEST_P"); BlockP blockP(nullptr, "TEST_P");
// test initial state // test initial state
ASSERT_CL(equal(0.2f, blockP.getKP())); ASSERT_CL(equal(0.2f, blockP.getKP()));
ASSERT_CL(equal(0.0f, blockP.getDt())); ASSERT_CL(equal(0.0f, blockP.getDt()));
@@ -331,7 +331,7 @@ int blockPTest()
int blockPITest() int blockPITest()
{ {
printf("Test BlockPI\t\t\t: "); printf("Test BlockPI\t\t\t: ");
BlockPI blockPI(NULL, "TEST"); BlockPI blockPI(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.2f, blockPI.getKP())); ASSERT_CL(equal(0.2f, blockPI.getKP()));
ASSERT_CL(equal(0.1f, blockPI.getKI())); ASSERT_CL(equal(0.1f, blockPI.getKI()));
@@ -353,7 +353,7 @@ int blockPITest()
int blockPDTest() int blockPDTest()
{ {
printf("Test BlockPD\t\t\t: "); printf("Test BlockPD\t\t\t: ");
BlockPD blockPD(NULL, "TEST"); BlockPD blockPD(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.2f, blockPD.getKP())); ASSERT_CL(equal(0.2f, blockPD.getKP()));
ASSERT_CL(equal(0.01f, blockPD.getKD())); ASSERT_CL(equal(0.01f, blockPD.getKD()));
@@ -378,7 +378,7 @@ int blockPDTest()
int blockPIDTest() int blockPIDTest()
{ {
printf("Test BlockPID\t\t\t: "); printf("Test BlockPID\t\t\t: ");
BlockPID blockPID(NULL, "TEST"); BlockPID blockPID(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.2f, blockPID.getKP())); ASSERT_CL(equal(0.2f, blockPID.getKP()));
ASSERT_CL(equal(0.1f, blockPID.getKI())); ASSERT_CL(equal(0.1f, blockPID.getKI()));
@@ -408,7 +408,7 @@ int blockPIDTest()
int blockOutputTest() int blockOutputTest()
{ {
printf("Test BlockOutput\t\t: "); printf("Test BlockOutput\t\t: ");
BlockOutput blockOutput(NULL, "TEST"); BlockOutput blockOutput(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.0f, blockOutput.getDt())); ASSERT_CL(equal(0.0f, blockOutput.getDt()));
ASSERT_CL(equal(0.5f, blockOutput.get())); ASSERT_CL(equal(0.5f, blockOutput.get()));
@@ -431,7 +431,7 @@ int blockRandUniformTest()
{ {
srand(1234); srand(1234);
printf("Test BlockRandUniform\t\t: "); printf("Test BlockRandUniform\t\t: ");
BlockRandUniform blockRandUniform(NULL, "TEST"); BlockRandUniform blockRandUniform(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.0f, blockRandUniform.getDt())); ASSERT_CL(equal(0.0f, blockRandUniform.getDt()));
ASSERT_CL(equal(-1.0f, blockRandUniform.getMin())); ASSERT_CL(equal(-1.0f, blockRandUniform.getMin()));
@@ -457,7 +457,7 @@ int blockRandGaussTest()
{ {
srand(1234); srand(1234);
printf("Test BlockRandGauss\t\t: "); printf("Test BlockRandGauss\t\t: ");
BlockRandGauss blockRandGauss(NULL, "TEST"); BlockRandGauss blockRandGauss(nullptr, "TEST");
// test initial state // test initial state
ASSERT_CL(equal(0.0f, blockRandGauss.getDt())); ASSERT_CL(equal(0.0f, blockRandGauss.getDt()));
ASSERT_CL(equal(1.0f, blockRandGauss.getMean())); ASSERT_CL(equal(1.0f, blockRandGauss.getMean()));
@@ -486,7 +486,7 @@ int blockRandGaussTest()
int blockStatsTest() int blockStatsTest()
{ {
printf("Test BlockStats\t\t\t: "); printf("Test BlockStats\t\t\t: ");
BlockStats<float, 1> stats(NULL, "TEST"); BlockStats<float, 1> stats(nullptr, "TEST");
ASSERT_CL(equal(0.0f, stats.getMean()(0))); ASSERT_CL(equal(0.0f, stats.getMean()(0)));
ASSERT_CL(equal(0.0f, stats.getStdDev()(0))); ASSERT_CL(equal(0.0f, stats.getStdDev()(0)));
stats.update(matrix::Scalar<float>(1.0f)); stats.update(matrix::Scalar<float>(1.0f));
@@ -504,7 +504,7 @@ int blockDelayTest()
{ {
printf("Test BlockDelay\t\t\t: "); printf("Test BlockDelay\t\t\t: ");
using namespace matrix; using namespace matrix;
BlockDelay<float, 2, 1, 3> delay(NULL, "TEST"); BlockDelay<float, 2, 1, 3> delay(nullptr, "TEST");
Vector2f u1(1, 2); Vector2f u1(1, 2);
Vector2f y1 = delay.update(u1); Vector2f y1 = delay.update(u1);
ASSERT_CL(equal(y1(0), u1(0))); ASSERT_CL(equal(y1(0), u1(0)));
+1 -1
View File
@@ -288,7 +288,7 @@ private:
}; };
Ekf2::Ekf2(): Ekf2::Ekf2():
SuperBlock(NULL, "EKF"), SuperBlock(nullptr, "EKF"),
_replay_mode(false), _replay_mode(false),
_publish_replay_mode(0), _publish_replay_mode(0),
_att_pub(nullptr), _att_pub(nullptr),
@@ -364,9 +364,9 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_actuators_0_pub(nullptr), _actuators_0_pub(nullptr),
_actuators_2_pub(nullptr), _actuators_2_pub(nullptr),
_rates_sp_id(0), _rates_sp_id(nullptr),
_actuators_id(0), _actuators_id(nullptr),
_attitude_setpoint_id(0), _attitude_setpoint_id(nullptr),
/* performance counters */ /* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fwa_dt")), _loop_perf(perf_alloc(PC_ELAPSED, "fwa_dt")),
@@ -557,7 +557,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_fw_pos_ctrl_status_pub(nullptr), _fw_pos_ctrl_status_pub(nullptr),
/* publication ID */ /* publication ID */
_attitude_setpoint_id(0), _attitude_setpoint_id(nullptr),
/* states */ /* states */
_ctrl_state(), _ctrl_state(),
@@ -20,7 +20,7 @@ static const char *msg_label = "[lpe] "; // rate of land detector correction
BlockLocalPositionEstimator::BlockLocalPositionEstimator() : BlockLocalPositionEstimator::BlockLocalPositionEstimator() :
// this block has no parent, and has name LPE // this block has no parent, and has name LPE
SuperBlock(NULL, "LPE"), SuperBlock(nullptr, "LPE"),
// subscriptions, set rate, add to list // subscriptions, set rate, add to list
_sub_armed(ORB_ID(actuator_armed), 1000 / 2, 0, &getSubscriptions()), _sub_armed(ORB_ID(actuator_armed), 1000 / 2, 0, &getSubscriptions()),
_sub_land(ORB_ID(vehicle_land_detected), 1000 / 2, 0, &getSubscriptions()), _sub_land(ORB_ID(vehicle_land_detected), 1000 / 2, 0, &getSubscriptions()),
@@ -44,8 +44,8 @@ BlockLocalPositionEstimator::BlockLocalPositionEstimator() :
_sub_dist2(ORB_ID(distance_sensor), 1000 / 10, 2, &getSubscriptions()), _sub_dist2(ORB_ID(distance_sensor), 1000 / 10, 2, &getSubscriptions()),
_sub_dist3(ORB_ID(distance_sensor), 1000 / 10, 3, &getSubscriptions()), _sub_dist3(ORB_ID(distance_sensor), 1000 / 10, 3, &getSubscriptions()),
_dist_subs(), _dist_subs(),
_sub_lidar(NULL), _sub_lidar(nullptr),
_sub_sonar(NULL), _sub_sonar(nullptr),
// publications // publications
_pub_lpos(ORB_ID(vehicle_local_position), -1, &getPublications()), _pub_lpos(ORB_ID(vehicle_local_position), -1, &getPublications()),
@@ -223,7 +223,7 @@ void BlockLocalPositionEstimator::update()
// auto-detect connected rangefinders while not armed // auto-detect connected rangefinders while not armed
bool armedState = _sub_armed.get().armed; bool armedState = _sub_armed.get().armed;
if (!armedState && (_sub_lidar == NULL || _sub_sonar == NULL)) { if (!armedState && (_sub_lidar == nullptr || _sub_sonar == nullptr)) {
// detect distance sensors // detect distance sensors
for (int i = 0; i < N_DIST_SUBS; i++) { for (int i = 0; i < N_DIST_SUBS; i++) {
@@ -238,13 +238,13 @@ void BlockLocalPositionEstimator::update()
if (s->get().type == \ if (s->get().type == \
distance_sensor_s::MAV_DISTANCE_SENSOR_LASER && distance_sensor_s::MAV_DISTANCE_SENSOR_LASER &&
_sub_lidar == NULL) { _sub_lidar == nullptr) {
_sub_lidar = s; _sub_lidar = s;
mavlink_and_console_log_info(&mavlink_log_pub, "%sLidar detected with ID %i", msg_label, i); mavlink_and_console_log_info(&mavlink_log_pub, "%sLidar detected with ID %i", msg_label, i);
} else if (s->get().type == \ } else if (s->get().type == \
distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND && distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND &&
_sub_sonar == NULL) { _sub_sonar == nullptr) {
_sub_sonar = s; _sub_sonar = s;
mavlink_and_console_log_info(&mavlink_log_pub, "%sSonar detected with ID %i", msg_label, i); mavlink_and_console_log_info(&mavlink_log_pub, "%sSonar detected with ID %i", msg_label, i);
} }
@@ -302,8 +302,8 @@ void BlockLocalPositionEstimator::update()
bool gpsUpdated = (_fusion.get() & FUSE_GPS) && _sub_gps.updated(); bool gpsUpdated = (_fusion.get() & FUSE_GPS) && _sub_gps.updated();
bool visionUpdated = (_fusion.get() & FUSE_VIS_POS) && _sub_vision_pos.updated(); bool visionUpdated = (_fusion.get() & FUSE_VIS_POS) && _sub_vision_pos.updated();
bool mocapUpdated = _sub_mocap.updated(); bool mocapUpdated = _sub_mocap.updated();
bool lidarUpdated = (_sub_lidar != NULL) && _sub_lidar->updated(); bool lidarUpdated = (_sub_lidar != nullptr) && _sub_lidar->updated();
bool sonarUpdated = (_sub_sonar != NULL) && _sub_sonar->updated(); bool sonarUpdated = (_sub_sonar != nullptr) && _sub_sonar->updated();
bool landUpdated = landed() bool landUpdated = landed()
&& ((_timeStamp - _time_last_land) > 1.0e6f / LAND_RATE); // throttle rate && ((_timeStamp - _time_last_land) > 1.0e6f / LAND_RATE); // throttle rate
@@ -115,7 +115,7 @@ int local_position_estimator_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
13500, 13500,
local_position_estimator_thread_main, local_position_estimator_thread_main,
(argv && argc > 2) ? (char *const *) &argv[2] : (char *const *) NULL); (argv && argc > 2) ? (char *const *) &argv[2] : (char *const *) nullptr);
return 0; return 0;
} }
+1 -1
View File
@@ -136,7 +136,7 @@ void LogWriterFile::thread_stop()
notify(); notify();
// wait for thread to complete // wait for thread to complete
int ret = pthread_join(_thread, NULL); int ret = pthread_join(_thread, nullptr);
if (ret) { if (ret) {
PX4_WARN("join failed: %d", ret); PX4_WARN("join failed: %d", ret);
+6 -6
View File
@@ -268,12 +268,12 @@ void Logger::run_trampoline(int argc, char *argv[])
int myoptind = 1; int myoptind = 1;
int ch; int ch;
const char *myoptarg = NULL; const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "r:b:etfm:q:", &myoptind, &myoptarg)) != EOF) { while ((ch = px4_getopt(argc, argv, "r:b:etfm:q:", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'r': { case 'r': {
unsigned long r = strtoul(myoptarg, NULL, 10); unsigned long r = strtoul(myoptarg, nullptr, 10);
if (r <= 0) { if (r <= 0) {
r = 1e6; r = 1e6;
@@ -288,7 +288,7 @@ void Logger::run_trampoline(int argc, char *argv[])
break; break;
case 'b': { case 'b': {
unsigned long s = strtoul(myoptarg, NULL, 10); unsigned long s = strtoul(myoptarg, nullptr, 10);
if (s < 1) { if (s < 1) {
s = 1; s = 1;
@@ -325,7 +325,7 @@ void Logger::run_trampoline(int argc, char *argv[])
break; break;
case 'q': case 'q':
queue_size = strtoul(myoptarg, NULL, 10); queue_size = strtoul(myoptarg, nullptr, 10);
if (queue_size == 0) { if (queue_size == 0) {
queue_size = 1; queue_size = 1;
@@ -586,7 +586,7 @@ int Logger::add_topics_from_file(const char *fname)
/* open the topic list file */ /* open the topic list file */
fp = fopen(fname, "r"); fp = fopen(fname, "r");
if (fp == NULL) { if (fp == nullptr) {
return -1; return -1;
} }
@@ -596,7 +596,7 @@ int Logger::add_topics_from_file(const char *fname)
/* get a line, bail on error/EOF */ /* get a line, bail on error/EOF */
line[0] = '\0'; line[0] = '\0';
if (fgets(line, sizeof(line), fp) == NULL) { if (fgets(line, sizeof(line), fp) == nullptr) {
break; break;
} }
+8 -8
View File
@@ -64,7 +64,7 @@ static const char *kTmpData = MOUNTPOINT "/$log$.txt";
//------------------------------------------------------------------- //-------------------------------------------------------------------
static bool static bool
stat_file(const char *file, time_t *date = 0, uint32_t *size = 0) stat_file(const char *file, time_t *date = nullptr, uint32_t *size = nullptr)
{ {
struct stat st; struct stat st;
@@ -89,7 +89,7 @@ MavlinkLogHandler::new_instance(Mavlink *mavlink)
//------------------------------------------------------------------- //-------------------------------------------------------------------
MavlinkLogHandler::MavlinkLogHandler(Mavlink *mavlink) MavlinkLogHandler::MavlinkLogHandler(Mavlink *mavlink)
: MavlinkStream(mavlink) : MavlinkStream(mavlink)
, _pLogHandlerHelper(0) , _pLogHandlerHelper(nullptr)
{ {
} }
@@ -184,7 +184,7 @@ MavlinkLogHandler::_log_request_list(const mavlink_message_t *msg)
//-- Is this a new request? //-- Is this a new request?
if ((request.end - request.start) > _pLogHandlerHelper->log_count) { if ((request.end - request.start) > _pLogHandlerHelper->log_count) {
delete _pLogHandlerHelper; delete _pLogHandlerHelper;
_pLogHandlerHelper = NULL; _pLogHandlerHelper = nullptr;
} }
} }
@@ -269,7 +269,7 @@ MavlinkLogHandler::_log_request_erase(const mavlink_message_t * /*msg*/)
*/ */
if (_pLogHandlerHelper) { if (_pLogHandlerHelper) {
delete _pLogHandlerHelper; delete _pLogHandlerHelper;
_pLogHandlerHelper = 0; _pLogHandlerHelper = nullptr;
} }
//-- Delete all logs //-- Delete all logs
@@ -305,7 +305,7 @@ MavlinkLogHandler::_log_request_end(const mavlink_message_t * /*msg*/)
if (_pLogHandlerHelper) { if (_pLogHandlerHelper) {
delete _pLogHandlerHelper; delete _pLogHandlerHelper;
_pLogHandlerHelper = 0; _pLogHandlerHelper = nullptr;
} }
} }
@@ -378,7 +378,7 @@ LogListHelper::LogListHelper()
, current_log_size(0) , current_log_size(0)
, current_log_data_offset(0) , current_log_data_offset(0)
, current_log_data_remaining(0) , current_log_data_remaining(0)
, current_log_filep(0) , current_log_filep(nullptr)
{ {
_init(); _init();
} }
@@ -435,7 +435,7 @@ LogListHelper::open_for_transmit()
{ {
if (current_log_filep) { if (current_log_filep) {
::fclose(current_log_filep); ::fclose(current_log_filep);
current_log_filep = 0; current_log_filep = nullptr;
} }
current_log_filep = ::fopen(current_log_filename, "rb"); current_log_filep = ::fopen(current_log_filename, "rb");
@@ -605,7 +605,7 @@ LogListHelper::_get_log_time_size(const char *path, const char *file, time_t &da
if (sscanf(&file[3], "%u", &u) == 1) { if (sscanf(&file[3], "%u", &u) == 1) {
date += (u * 60); date += (u * 60);
if (stat_file(path, 0, &size)) { if (stat_file(path, nullptr, &size)) {
return true; return true;
} }
} }
+8 -8
View File
@@ -1062,7 +1062,7 @@ Mavlink::find_broadcast_address()
#else #else
// On Linux, we can determine the required size of the // On Linux, we can determine the required size of the
// buffer first by providing NULL to ifc_req. // buffer first by providing NULL to ifc_req.
ifconf.ifc_req = NULL; ifconf.ifc_req = nullptr;
ifconf.ifc_len = 0; ifconf.ifc_len = 0;
ret = ioctl(_socket_fd, SIOCGIFCONF, &ifconf); ret = ioctl(_socket_fd, SIOCGIFCONF, &ifconf);
@@ -1455,7 +1455,7 @@ Mavlink::message_buffer_init(int size)
int ret; int ret;
if (_message_buffer.data == 0) { if (_message_buffer.data == nullptr) {
ret = PX4_ERROR; ret = PX4_ERROR;
_message_buffer.size = 0; _message_buffer.size = 0;
@@ -1718,7 +1718,7 @@ Mavlink::task_main(int argc, char *argv[])
* set error flag instead */ * set error flag instead */
bool err_flag = false; bool err_flag = false;
int myoptind = 1; int myoptind = 1;
const char *myoptarg = NULL; const char *myoptarg = nullptr;
#ifdef __PX4_POSIX #ifdef __PX4_POSIX
char *eptr; char *eptr;
int temp_int_arg; int temp_int_arg;
@@ -1727,7 +1727,7 @@ Mavlink::task_main(int argc, char *argv[])
while ((ch = px4_getopt(argc, argv, "b:r:d:u:o:m:t:fpvwx", &myoptind, &myoptarg)) != EOF) { while ((ch = px4_getopt(argc, argv, "b:r:d:u:o:m:t:fpvwx", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'b': case 'b':
_baudrate = strtoul(myoptarg, NULL, 10); _baudrate = strtoul(myoptarg, nullptr, 10);
if (_baudrate < 9600 || _baudrate > 3000000) { if (_baudrate < 9600 || _baudrate > 3000000) {
warnx("invalid baud rate '%s'", myoptarg); warnx("invalid baud rate '%s'", myoptarg);
@@ -1737,7 +1737,7 @@ Mavlink::task_main(int argc, char *argv[])
break; break;
case 'r': case 'r':
_datarate = strtoul(myoptarg, NULL, 10); _datarate = strtoul(myoptarg, nullptr, 10);
if (_datarate < 10 || _datarate > MAX_DATA_RATE) { if (_datarate < 10 || _datarate > MAX_DATA_RATE) {
warnx("invalid data rate '%s'", myoptarg); warnx("invalid data rate '%s'", myoptarg);
@@ -1905,7 +1905,7 @@ Mavlink::task_main(int argc, char *argv[])
} }
/* initialize send mutex */ /* initialize send mutex */
pthread_mutex_init(&_send_mutex, NULL); pthread_mutex_init(&_send_mutex, nullptr);
/* if we are passing on mavlink messages, we need to prepare a buffer for this instance */ /* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
if (_forwarding_on || _ftp_on) { if (_forwarding_on || _ftp_on) {
@@ -1919,7 +1919,7 @@ Mavlink::task_main(int argc, char *argv[])
} }
/* initialize message buffer mutex */ /* initialize message buffer mutex */
pthread_mutex_init(&_message_buffer_mutex, NULL); pthread_mutex_init(&_message_buffer_mutex, nullptr);
} }
/* Initialize system properties */ /* Initialize system properties */
@@ -2366,7 +2366,7 @@ Mavlink::task_main(int argc, char *argv[])
} }
/* first wait for threads to complete before tearing down anything */ /* first wait for threads to complete before tearing down anything */
pthread_join(_receive_thread, NULL); pthread_join(_receive_thread, nullptr);
delete _subscribe_to_stream; delete _subscribe_to_stream;
_subscribe_to_stream = nullptr; _subscribe_to_stream = nullptr;
@@ -74,7 +74,7 @@ MavlinkFtpTest::~MavlinkFtpTest()
void MavlinkFtpTest::_init(void) void MavlinkFtpTest::_init(void)
{ {
_expected_seq_number = 0; _expected_seq_number = 0;
_ftp_server = new MavlinkFTP(NULL); _ftp_server = new MavlinkFTP(nullptr);
_ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_generic, this); _ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_generic, this);
_cleanup_microsd(); _cleanup_microsd();
@@ -412,8 +412,8 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_v_rates_sp_pub(nullptr), _v_rates_sp_pub(nullptr),
_actuators_0_pub(nullptr), _actuators_0_pub(nullptr),
_controller_status_pub(nullptr), _controller_status_pub(nullptr),
_rates_sp_id(0), _rates_sp_id(nullptr),
_actuators_id(0), _actuators_id(nullptr),
_actuators_0_circuit_breaker_enabled(false), _actuators_0_circuit_breaker_enabled(false),
@@ -385,7 +385,7 @@ MulticopterPositionControl *g_control;
} }
MulticopterPositionControl::MulticopterPositionControl() : MulticopterPositionControl::MulticopterPositionControl() :
SuperBlock(NULL, "MPC"), SuperBlock(nullptr, "MPC"),
_task_should_exit(false), _task_should_exit(false),
_control_task(-1), _control_task(-1),
_mavlink_log_pub(nullptr), _mavlink_log_pub(nullptr),
@@ -405,7 +405,7 @@ MulticopterPositionControl::MulticopterPositionControl() :
_att_sp_pub(nullptr), _att_sp_pub(nullptr),
_local_pos_sp_pub(nullptr), _local_pos_sp_pub(nullptr),
_global_vel_sp_pub(nullptr), _global_vel_sp_pub(nullptr),
_attitude_setpoint_id(0), _attitude_setpoint_id(nullptr),
_vehicle_status{}, _vehicle_status{},
_vehicle_land_detected{}, _vehicle_land_detected{},
_ctrl_state{}, _ctrl_state{},
+2 -2
View File
@@ -332,14 +332,14 @@ Geofence::loadFromFile(const char *filename)
/* open the mixer definition file */ /* open the mixer definition file */
fp = fopen(GEOFENCE_FILENAME, "r"); fp = fopen(GEOFENCE_FILENAME, "r");
if (fp == NULL) { if (fp == nullptr) {
return PX4_ERROR; return PX4_ERROR;
} }
/* create geofence points from valid lines and store in DM */ /* create geofence points from valid lines and store in DM */
for (;;) { for (;;) {
/* get a line, bail on error/EOF */ /* get a line, bail on error/EOF */
if (fgets(line, sizeof(line), fp) == NULL) { if (fgets(line, sizeof(line), fp) == nullptr) {
break; break;
} }
+1 -1
View File
@@ -100,7 +100,7 @@ Navigator *g_navigator;
} }
Navigator::Navigator() : Navigator::Navigator() :
SuperBlock(NULL, "NAV"), SuperBlock(nullptr, "NAV"),
_task_should_exit(false), _task_should_exit(false),
_navigator_task(-1), _navigator_task(-1),
_mavlink_log_pub(nullptr), _mavlink_log_pub(nullptr),
@@ -153,7 +153,7 @@ int position_estimator_inav_main(int argc, char *argv[])
position_estimator_inav_task = px4_task_spawn_cmd("position_estimator_inav", position_estimator_inav_task = px4_task_spawn_cmd("position_estimator_inav",
SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4600, SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4600,
position_estimator_inav_thread_main, position_estimator_inav_thread_main,
(argv && argc > 2) ? (char *const *) &argv[2] : (char *const *) NULL); (argv && argc > 2) ? (char *const *) &argv[2] : (char *const *) nullptr);
return 0; return 0;
} }
@@ -385,7 +385,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* advertise */ /* advertise */
orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos); orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos);
orb_advert_t vehicle_global_position_pub = NULL; orb_advert_t vehicle_global_position_pub = nullptr;
struct position_estimator_inav_params params; struct position_estimator_inav_params params;
memset(&params, 0, sizeof(params)); memset(&params, 0, sizeof(params));
@@ -1383,7 +1383,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.pressure_alt = sensor.baro_alt_meter; global_pos.pressure_alt = sensor.baro_alt_meter;
if (vehicle_global_position_pub == NULL) { if (vehicle_global_position_pub == nullptr) {
vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos); vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
} else { } else {
+1 -1
View File
@@ -55,7 +55,7 @@ using namespace simulator;
static px4_task_t g_sim_task = -1; static px4_task_t g_sim_task = -1;
Simulator *Simulator::_instance = NULL; Simulator *Simulator::_instance = nullptr;
Simulator *Simulator::getInstance() Simulator *Simulator::getInstance()
{ {
+1 -1
View File
@@ -744,7 +744,7 @@ void Simulator::pollForMAVLinkMessages(bool publish, int udp_port)
_vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
// got data from simulator, now activate the sending thread // got data from simulator, now activate the sending thread
pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL); pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, nullptr);
pthread_attr_destroy(&sender_thread_attr); pthread_attr_destroy(&sender_thread_attr);
mavlink_status_t udp_status = {}; mavlink_status_t udp_status = {};
+1 -1
View File
@@ -42,7 +42,7 @@
#include "battery.h" #include "battery.h"
Battery::Battery() : Battery::Battery() :
SuperBlock(NULL, "BAT"), SuperBlock(nullptr, "BAT"),
_param_v_empty(this, "V_EMPTY"), _param_v_empty(this, "V_EMPTY"),
_param_v_full(this, "V_CHARGED"), _param_v_full(this, "V_CHARGED"),
_param_n_cells(this, "N_CELLS"), _param_n_cells(this, "N_CELLS"),
@@ -414,7 +414,7 @@ MultirotorMixer::mix(float *outputs, unsigned space, uint16_t *status_reg)
_delta_out_max = 0.0f; _delta_out_max = 0.0f;
// Notify saturation status // Notify saturation status
if (status_reg != NULL) { if (status_reg != nullptr) {
(*status_reg) = _saturation_status.value; (*status_reg) = _saturation_status.value;
} }
@@ -127,7 +127,7 @@ int uORBTest::UnitTest::pubsublatency_main(void)
sprintf(fname, PX4_ROOTFSDIR"/fs/microsd/timings%u.txt", timingsgroup); sprintf(fname, PX4_ROOTFSDIR"/fs/microsd/timings%u.txt", timingsgroup);
FILE *f = fopen(fname, "w"); FILE *f = fopen(fname, "w");
if (f == NULL) { if (f == nullptr) {
warnx("Error opening file!\n"); warnx("Error opening file!\n");
return uORB::ERROR; return uORB::ERROR;
} }
@@ -472,7 +472,7 @@ int uORBTest::UnitTest::test_multi2()
orb_data_fd[i] = orb_subscribe_multi(ORB_ID(orb_test_medium_multi), i); orb_data_fd[i] = orb_subscribe_multi(ORB_ID(orb_test_medium_multi), i);
} }
char *const args[1] = { NULL }; char *const args[1] = { nullptr };
int pubsub_task = px4_task_spawn_cmd("uorb_test_multi", int pubsub_task = px4_task_spawn_cmd("uorb_test_multi",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
@@ -761,7 +761,7 @@ int uORBTest::UnitTest::test_queue_poll_notify()
_thread_should_exit = false; _thread_should_exit = false;
char *const args[1] = { NULL }; char *const args[1] = { nullptr };
int pubsub_task = px4_task_spawn_cmd("uorb_test_queue", int pubsub_task = px4_task_spawn_cmd("uorb_test_queue",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MIN + 5, SCHED_PRIORITY_MIN + 5,
@@ -388,7 +388,7 @@ ACCELSIM::transfer(uint8_t *send, uint8_t *recv, unsigned len)
// Get data from the simulator // Get data from the simulator
Simulator *sim = Simulator::getInstance(); Simulator *sim = Simulator::getInstance();
if (sim == NULL) { if (sim == nullptr) {
return ENODEV; return ENODEV;
} }
@@ -1159,7 +1159,7 @@ accelsim_main(int argc, char *argv[])
enum Rotation rotation = ROTATION_NONE; enum Rotation rotation = ROTATION_NONE;
int ret; int ret;
int myoptind = 1; int myoptind = 1;
const char *myoptarg = NULL; const char *myoptarg = nullptr;
/* jump over start/off/etc and look at options first */ /* jump over start/off/etc and look at options first */
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) { while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
@@ -425,7 +425,7 @@ AirspeedSim::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, uns
// this is equivalent to the collect phase // this is equivalent to the collect phase
Simulator *sim = Simulator::getInstance(); Simulator *sim = Simulator::getInstance();
if (sim == NULL) { if (sim == nullptr) {
PX4_ERR("Error BARO_SIM::transfer no simulator"); PX4_ERR("Error BARO_SIM::transfer no simulator");
return -ENODEV; return -ENODEV;
} }
+2 -2
View File
@@ -620,7 +620,7 @@ BAROSIM::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigne
/* read requested */ /* read requested */
Simulator *sim = Simulator::getInstance(); Simulator *sim = Simulator::getInstance();
if (sim == NULL) { if (sim == nullptr) {
PX4_ERR("Error BAROSIM_DEV::transfer no simulator"); PX4_ERR("Error BAROSIM_DEV::transfer no simulator");
return -ENODEV; return -ENODEV;
} }
@@ -785,7 +785,7 @@ start()
if (g_barosim != nullptr && OK != g_barosim->init()) { if (g_barosim != nullptr && OK != g_barosim->init()) {
delete g_barosim; delete g_barosim;
g_barosim = NULL; g_barosim = nullptr;
PX4_ERR("bus init failed"); PX4_ERR("bus init failed");
return false; return false;
} }
@@ -641,16 +641,16 @@ rgbledsim_main(int argc, char *argv[])
/* jump over start/off/etc and look at options first */ /* jump over start/off/etc and look at options first */
int myoptind = 1; int myoptind = 1;
const char *myoptarg = NULL; const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) { while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'a': case 'a':
rgbledadr = strtol(myoptarg, NULL, 0); rgbledadr = strtol(myoptarg, nullptr, 0);
break; break;
case 'b': case 'b':
i2cdevice = strtol(myoptarg, NULL, 0); i2cdevice = strtol(myoptarg, nullptr, 0);
break; break;
default: default:
@@ -783,9 +783,9 @@ rgbledsim_main(int argc, char *argv[])
} }
rgbled_rgbset_t v; rgbled_rgbset_t v;
v.red = strtol(argv[2], NULL, 0); v.red = strtol(argv[2], nullptr, 0);
v.green = strtol(argv[3], NULL, 0); v.green = strtol(argv[3], nullptr, 0);
v.blue = strtol(argv[4], NULL, 0); v.blue = strtol(argv[4], nullptr, 0);
ret = h.ioctl(RGBLED_SET_RGB, (unsigned long)&v); ret = h.ioctl(RGBLED_SET_RGB, (unsigned long)&v);
ret = h.ioctl(RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_ON); ret = h.ioctl(RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_ON);
DevMgr::releaseHandle(h); DevMgr::releaseHandle(h);
+5 -5
View File
@@ -159,7 +159,7 @@ static int mkpath(const char *path, mode_t mode)
status = 0; status = 0;
pp = copypath; pp = copypath;
while (status == 0 && (sp = strchr(pp, '/')) != 0) { while (status == 0 && (sp = strchr(pp, '/')) != nullptr) {
if (sp != pp) { if (sp != pp) {
/* Neither root nor double slash in path */ /* Neither root nor double slash in path */
*sp = '\0'; *sp = '\0';
@@ -214,7 +214,7 @@ static void run_cmd(const vector<string> &appargs, bool exit_on_fail, bool silen
++i; ++i;
} }
arg[i] = (char *)0; arg[i] = (char *)nullptr;
int retval = apps[command](i, (char **)arg); int retval = apps[command](i, (char **)arg);
@@ -310,9 +310,9 @@ int main(int argc, char **argv)
sig_fpe.sa_handler = _SigFpeHandler; sig_fpe.sa_handler = _SigFpeHandler;
sig_fpe.sa_flags = 0;// not SA_RESTART!; sig_fpe.sa_flags = 0;// not SA_RESTART!;
sigaction(SIGINT, &sig_int, NULL); sigaction(SIGINT, &sig_int, nullptr);
//sigaction(SIGTERM, &sig_int, NULL); //sigaction(SIGTERM, &sig_int, NULL);
sigaction(SIGFPE, &sig_fpe, NULL); sigaction(SIGFPE, &sig_fpe, nullptr);
set_cpu_scaling(); set_cpu_scaling();
@@ -514,7 +514,7 @@ int main(int argc, char **argv)
term.c_lflag &= ~ICANON; term.c_lflag &= ~ICANON;
term.c_lflag &= ~ECHO; term.c_lflag &= ~ECHO;
tcsetattr(0, TCSANOW, &term); tcsetattr(0, TCSANOW, &term);
setbuf(stdin, NULL); setbuf(stdin, nullptr);
while (!_ExitFlag) { while (!_ExitFlag) {
@@ -108,7 +108,7 @@ static void *entry_adapter(void *ptr)
px4_task_exit(0); px4_task_exit(0);
PX4_DEBUG("After px4_task_exit"); PX4_DEBUG("After px4_task_exit");
return NULL; return nullptr;
} }
void void
@@ -134,10 +134,10 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
struct sched_param param = {}; struct sched_param param = {};
// Calculate argc // Calculate argc
while (p != (char *)0) { while (p != (char *)nullptr) {
p = argv[argc]; p = argv[argc];
if (p == (char *)0) { if (p == (char *)nullptr) {
break; break;
} }
@@ -165,7 +165,7 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
} }
// Must add NULL at end of argv // Must add NULL at end of argv
taskdata->argv[argc] = (char *)0; taskdata->argv[argc] = (char *)nullptr;
PX4_DEBUG("starting task %s", name); PX4_DEBUG("starting task %s", name);
@@ -249,7 +249,7 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
if (rv == EPERM) { if (rv == EPERM) {
//printf("WARNING: NOT RUNING AS ROOT, UNABLE TO RUN REALTIME THREADS\n"); //printf("WARNING: NOT RUNING AS ROOT, UNABLE TO RUN REALTIME THREADS\n");
rv = pthread_create(&taskmap[taskid].pid, NULL, &entry_adapter, (void *) taskdata); rv = pthread_create(&taskmap[taskid].pid, nullptr, &entry_adapter, (void *) taskdata);
if (rv != 0) { if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to create thread %d %d\n", rv, errno); PX4_ERR("px4_task_spawn_cmd: failed to create thread %d %d\n", rv, errno);
@@ -293,7 +293,7 @@ int px4_task_delete(px4_task_t id)
if (pthread_self() == pid) { if (pthread_self() == pid) {
taskmap[id].isused = false; taskmap[id].isused = false;
pthread_mutex_unlock(&task_mutex); pthread_mutex_unlock(&task_mutex);
pthread_exit(0); pthread_exit(nullptr);
} else { } else {
rv = pthread_cancel(pid); rv = pthread_cancel(pid);
+1 -1
View File
@@ -192,7 +192,7 @@ int motor_ramp_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT + 40, SCHED_PRIORITY_DEFAULT + 40,
2000, 2000,
motor_ramp_thread_main, motor_ramp_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL); (argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
return 0; return 0;
usage("unrecognized command"); usage("unrecognized command");
+5 -5
View File
@@ -399,7 +399,7 @@ bool MixerTest::mixerTest()
/* mix */ /* mix */
should_prearm = true; should_prearm = true;
mixed = mixer_group.mix(&outputs[0], output_max, NULL); mixed = mixer_group.mix(&outputs[0], output_max, nullptr);
pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min,
r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
@@ -440,7 +440,7 @@ bool MixerTest::mixerTest()
while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US + 2 * sleep_quantum_us) { while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US + 2 * sleep_quantum_us) {
/* mix */ /* mix */
mixed = mixer_group.mix(&outputs[0], output_max, NULL); mixed = mixer_group.mix(&outputs[0], output_max, nullptr);
pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min,
r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
@@ -484,7 +484,7 @@ bool MixerTest::mixerTest()
} }
/* mix */ /* mix */
mixed = mixer_group.mix(&outputs[0], output_max, NULL); mixed = mixer_group.mix(&outputs[0], output_max, nullptr);
pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min,
r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
@@ -512,7 +512,7 @@ bool MixerTest::mixerTest()
while (hrt_elapsed_time(&starttime) < 600000) { while (hrt_elapsed_time(&starttime) < 600000) {
/* mix */ /* mix */
mixed = mixer_group.mix(&outputs[0], output_max, NULL); mixed = mixer_group.mix(&outputs[0], output_max, nullptr);
pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min,
r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
@@ -549,7 +549,7 @@ bool MixerTest::mixerTest()
while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) { while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) {
/* mix */ /* mix */
mixed = mixer_group.mix(&outputs[0], output_max, NULL); mixed = mixer_group.mix(&outputs[0], output_max, nullptr);
pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min,
r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);