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

View File

@@ -1062,7 +1062,7 @@ Mavlink::find_broadcast_address()
#else
// On Linux, we can determine the required size of the
// buffer first by providing NULL to ifc_req.
ifconf.ifc_req = NULL;
ifconf.ifc_req = nullptr;
ifconf.ifc_len = 0;
ret = ioctl(_socket_fd, SIOCGIFCONF, &ifconf);
@@ -1455,7 +1455,7 @@ Mavlink::message_buffer_init(int size)
int ret;
if (_message_buffer.data == 0) {
if (_message_buffer.data == nullptr) {
ret = PX4_ERROR;
_message_buffer.size = 0;
@@ -1718,7 +1718,7 @@ Mavlink::task_main(int argc, char *argv[])
* set error flag instead */
bool err_flag = false;
int myoptind = 1;
const char *myoptarg = NULL;
const char *myoptarg = nullptr;
#ifdef __PX4_POSIX
char *eptr;
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) {
switch (ch) {
case 'b':
_baudrate = strtoul(myoptarg, NULL, 10);
_baudrate = strtoul(myoptarg, nullptr, 10);
if (_baudrate < 9600 || _baudrate > 3000000) {
warnx("invalid baud rate '%s'", myoptarg);
@@ -1737,7 +1737,7 @@ Mavlink::task_main(int argc, char *argv[])
break;
case 'r':
_datarate = strtoul(myoptarg, NULL, 10);
_datarate = strtoul(myoptarg, nullptr, 10);
if (_datarate < 10 || _datarate > MAX_DATA_RATE) {
warnx("invalid data rate '%s'", myoptarg);
@@ -1905,7 +1905,7 @@ Mavlink::task_main(int argc, char *argv[])
}
/* 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 (_forwarding_on || _ftp_on) {
@@ -1919,7 +1919,7 @@ Mavlink::task_main(int argc, char *argv[])
}
/* initialize message buffer mutex */
pthread_mutex_init(&_message_buffer_mutex, NULL);
pthread_mutex_init(&_message_buffer_mutex, nullptr);
}
/* Initialize system properties */
@@ -2366,7 +2366,7 @@ Mavlink::task_main(int argc, char *argv[])
}
/* first wait for threads to complete before tearing down anything */
pthread_join(_receive_thread, NULL);
pthread_join(_receive_thread, nullptr);
delete _subscribe_to_stream;
_subscribe_to_stream = nullptr;