提交 92c91914 编写于 作者: Z zhuangli1987 提交者: Liangliang Zhang

chang null to nullptr

上级 12b18793
......@@ -36,8 +36,8 @@ static const char* const LC_LOG_SEVERITY_NAMES[NUM_SEVERITIES] = {
LogFileObject::LogFileObject(google::LogSeverity severity,
const char* base_filename)
: base_filename_selected_(base_filename != NULL),
base_filename_((base_filename != NULL) ? base_filename : ""),
: base_filename_selected_(base_filename != nullptr),
base_filename_((base_filename != nullptr) ? base_filename : ""),
base_filepath_(base_filename_),
symlink_basename_("UNKNOWN"),
filename_extension_(),
......@@ -51,9 +51,9 @@ LogFileObject::LogFileObject(google::LogSeverity severity,
LogFileObject::~LogFileObject() {
std::lock_guard<std::mutex> lock(lock_);
if (file_ != NULL) {
if (file_ != nullptr) {
fclose(file_);
file_ = NULL;
file_ = nullptr;
}
}
......@@ -62,9 +62,9 @@ void LogFileObject::SetBasename(const char* basename) {
base_filename_selected_ = true;
if (base_filename_ != basename) {
// Get rid of old log file since we are changing names
if (file_ != NULL) {
if (file_ != nullptr) {
fclose(file_);
file_ = NULL;
file_ = nullptr;
rollover_attempt_ = kRolloverAttemptFrequency - 1;
}
base_filename_ = basename;
......@@ -75,9 +75,9 @@ void LogFileObject::SetExtension(const char* ext) {
std::lock_guard<std::mutex> lock(lock_);
if (filename_extension_ != ext) {
// Get rid of old log file since we are changing names
if (file_ != NULL) {
if (file_ != nullptr) {
fclose(file_);
file_ = NULL;
file_ = nullptr;
rollover_attempt_ = kRolloverAttemptFrequency - 1;
}
filename_extension_ = ext;
......@@ -95,7 +95,7 @@ void LogFileObject::Flush() {
}
void LogFileObject::FlushUnlocked() {
if (file_ != NULL) {
if (file_ != nullptr) {
fflush(file_);
bytes_since_flush_ = 0;
}
......@@ -121,7 +121,7 @@ bool LogFileObject::CreateLogfile(const std::string& time_pid_string) {
#endif
file_ = fdopen(fd, "a"); // Make a FILE*.
if (file_ == NULL) { // Man, we're screwed!
if (file_ == nullptr) { // Man, we're screwed!
close(fd);
unlink(filename); // Erase the half-baked evidence: an unusable log file
return false;
......@@ -159,14 +159,14 @@ void LogFileObject::Write(bool force_flush, time_t timestamp,
if (static_cast<int>(file_length_ >> 20) >=
::apollo::cybertron::logger::MaxLogSize() ||
apollo::cybertron::logger::PidHasChanged()) {
if (file_ != NULL) fclose(file_);
file_ = NULL;
if (file_ != nullptr) fclose(file_);
file_ = nullptr;
file_length_ = bytes_since_flush_ = dropped_mem_length_ = 0;
rollover_attempt_ = kRolloverAttemptFrequency - 1;
}
// If there's no destination file, make one before outputting
if (file_ == NULL) {
if (file_ == nullptr) {
// Try to rollover the log file every 32 log messages. The only time
// this could matter would be when we have trouble creating the log
// file. If that happens, we'll lose lots of log messages, of course!
......@@ -231,7 +231,7 @@ void LogFileObject::Write(bool force_flush, time_t timestamp,
const std::string& file_header_string = file_header_stream.str();
const int header_len = file_header_string.size();
if (file_ == NULL) {
if (file_ == nullptr) {
return;
}
fwrite(file_header_string.data(), 1, header_len, file_);
......
......@@ -39,7 +39,7 @@ namespace logger {
int64_t CycleClock_Now() {
struct timeval tv;
gettimeofday(&tv, NULL);
gettimeofday(&tv, nullptr);
return static_cast<int64_t>(tv.tv_sec) * 1000000 + tv.tv_usec;
}
......@@ -53,7 +53,7 @@ static void GetHostName(std::string* hostname) {
static std::vector<std::string>* logging_directories_list;
const std::vector<std::string>& GetLoggingDirectories() {
if (logging_directories_list == NULL) {
if (logging_directories_list == nullptr) {
logging_directories_list = new std::vector<std::string>;
if (!FLAGS_log_dir.empty()) {
......
......@@ -63,10 +63,10 @@ void ModuleArgument::GetOptions(const int argc, char* const argv[]) {
int long_index = 0;
const std::string short_opts = "h::d:p:";
static const struct option long_opts[] = {
{"help", no_argument, NULL, 'h'},
{"dag_conf", required_argument, NULL, 'd'},
{"process_name", required_argument, NULL, 'p'},
{NULL, no_argument, NULL, 0}};
{"help", no_argument, nullptr, 'h'},
{"dag_conf", required_argument, nullptr, 'd'},
{"process_name", required_argument, nullptr, 'p'},
{NULL, no_argument, nullptr, 0}};
// log command for info
std::string cmd("");
......
......@@ -85,10 +85,10 @@ class ProtobufFactory {
google::protobuf::Message* GenerateMessageByType(
const std::string& type) const;
// Find a top-level message type by name. Returns NULL if not found.
// Find a top-level message type by name. Returns nullptr if not found.
const Descriptor* FindMessageTypeByName(const std::string& type) const;
// Find a service definition by name. Returns NULL if not found.
// Find a service definition by name. Returns nullptr if not found.
const google::protobuf::ServiceDescriptor* FindServiceByName(
const std::string& name) const;
......
......@@ -73,14 +73,14 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
* \param target_time The time at which to transform
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
const std::string& source_frame,
const cybertron::Time& target_time,
const float timeout_second = 0.01,
std::string* errstr = NULL) const;
std::string* errstr = nullptr) const;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
......@@ -91,7 +91,7 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
* time
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
......@@ -100,7 +100,7 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
const cybertron::Time& source_time,
const std::string& fixed_frame,
const float timeout_second = 0.01,
std::string* errstr = NULL) const;
std::string* errstr = nullptr) const;
private:
void SubscriptionCallback(
......
......@@ -61,14 +61,14 @@ class BufferInterface {
* \param time The time at which to transform
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
const std::string& source_frame,
const cybertron::Time& time,
const float timeout_second = 0.01,
std::string* errstr = NULL) const = 0;
std::string* errstr = nullptr) const = 0;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
......@@ -79,7 +79,7 @@ class BufferInterface {
* time
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
......@@ -88,7 +88,7 @@ class BufferInterface {
const cybertron::Time& source_time,
const std::string& fixed_frame,
const float timeout_second = 0.01,
std::string* errstr = NULL) const = 0;
std::string* errstr = nullptr) const = 0;
// Transform, simple api, with pre-allocation
template <typename T>
......
......@@ -90,7 +90,7 @@ void InteractiveGraphicsView::mouseMoveEvent(QMouseEvent *event) {
void InteractiveGraphicsView::mousePressEvent(QMouseEvent *event) {
if (event->button() == Qt::LeftButton) {
QPointF point = mapToScene(event->pos());
if (scene()->itemAt(point, transform()) == NULL) {
if (scene()->itemAt(point, transform()) == nullptr) {
last_mouse_pos_ = event->pos();
mouse_left_button_pressed_ = true;
......
......@@ -148,18 +148,18 @@ int main(int argc, char** argv) {
int long_index = 0;
const std::string short_opts = "f:c:k:o:alr:b:e:s:d:h";
static const struct option long_opts[] = {
{"files", required_argument, NULL, 'f'},
{"white-channel", required_argument, NULL, 'c'},
{"black-channel", required_argument, NULL, 'k'},
{"output", required_argument, NULL, 'o'},
{"all", no_argument, NULL, 'a'},
{"loop", no_argument, NULL, 'l'},
{"rate", required_argument, NULL, 'r'},
{"begin", required_argument, NULL, 'b'},
{"end", required_argument, NULL, 'e'},
{"start", required_argument, NULL, 's'},
{"delay", required_argument, NULL, 'd'},
{"help", no_argument, NULL, 'h'}};
{"files", required_argument, nullptr, 'f'},
{"white-channel", required_argument, nullptr, 'c'},
{"black-channel", required_argument, nullptr, 'k'},
{"output", required_argument, nullptr, 'o'},
{"all", no_argument, nullptr, 'a'},
{"loop", no_argument, nullptr, 'l'},
{"rate", required_argument, nullptr, 'r'},
{"begin", required_argument, nullptr, 'b'},
{"end", required_argument, nullptr, 'e'},
{"start", required_argument, nullptr, 's'},
{"delay", required_argument, nullptr, 'd'},
{"help", no_argument, nullptr, 'h'}};
std::vector<std::string> opt_file_vec;
std::vector<std::string> opt_output_vec;
......
......@@ -465,7 +465,7 @@ void Player::ReadCharFromStdin() {
timeval tv;
tv.tv_sec = 0;
tv.tv_usec = 0;
if (select(maxfd_, &testfd, NULL, NULL, &tv) <= 0) {
if (select(maxfd_, &testfd, nullptr, nullptr, &tv) <= 0) {
return;
}
auto ch = getc(stdin);
......
......@@ -154,7 +154,7 @@ void Reactor::ThreadFunc() {
/* block all signals in this thread */
sigset_t signal_set;
sigfillset(&signal_set);
pthread_sigmask(SIG_BLOCK, &signal_set, NULL);
pthread_sigmask(SIG_BLOCK, &signal_set, nullptr);
while (!shutdown_) {
Poll(100);
......
......@@ -48,7 +48,7 @@ void Participant::CreateFastRtpsParticipant(
eprosima::fastrtps::ParticipantListener* listener) {
uint32_t domain_id = 80;
const char* val = ::getenv("CYBER_DOMAIN_ID");
if (val != NULL) {
if (val != nullptr) {
try {
domain_id = std::stoi(val);
} catch (const std::exception& e) {
......
......@@ -135,7 +135,7 @@ bool Segment::OpenOrCreate() {
}
// attach managed_shm_
managed_shm_ = shmat(shmid, NULL, 0);
managed_shm_ = shmat(shmid, nullptr, 0);
if (managed_shm_ == reinterpret_cast<void*>(-1)) {
AERROR << "attach shm failed.";
shmctl(shmid, IPC_RMID, 0);
......@@ -213,7 +213,7 @@ bool Segment::OpenOnly() {
}
// attach managed_shm_
managed_shm_ = shmat(shmid, NULL, 0);
managed_shm_ = shmat(shmid, nullptr, 0);
if (managed_shm_ == reinterpret_cast<void*>(-1)) {
AERROR << "attach shm failed.";
return false;
......
......@@ -46,11 +46,11 @@ int TestCUDA() {
h_B[i] = rand()/(float)RAND_MAX;
}
float *d_A = NULL;
float *d_A = nullptr;
cudaMalloc((void **)&d_A, size);
float *d_B = NULL;
float *d_B = nullptr;
cudaMalloc((void **)&d_B, size);
float *d_C = NULL;
float *d_C = nullptr;
cudaMalloc((void **)&d_C, size);
cudaMemcpy(d_A, h_A, size, cudaMemcpyHostToDevice);
......
......@@ -84,7 +84,7 @@ class Factory {
/**
* @brief Creates and transfers membership of an object of type matching id.
* Need to register id before CreateObject is called. May return NULL
* Need to register id before CreateObject is called. May return nullptr
* silently.
* @param id The identifier of the class we which to instantiate
* @param args the object construction arguments
......
......@@ -69,7 +69,7 @@ template <typename T, typename std::enable_if<
bool DumpMessage(const std::shared_ptr<T>& msg,
const std::string& dump_dir = "/tmp") {
if (!msg) {
AWARN << "Message to be dumped is NULL!";
AWARN << "Message to be dumped is nullptr!";
}
auto type_name = T::descriptor()->full_name();
......
......@@ -81,8 +81,8 @@ Status ControllerAgent::Init(const ControlConf *control_conf) {
RegisterControllers(control_conf);
CHECK(InitializeConf(control_conf).ok()) << "Fail to initialize config.";
for (auto &controller : controller_list_) {
if (controller == NULL || !controller->Init(control_conf_).ok()) {
if (controller != NULL) {
if (controller == nullptr || !controller->Init(control_conf_).ok()) {
if (controller != nullptr) {
AERROR << "Controller <" << controller->Name() << "> init failed!";
return Status(ErrorCode::CONTROL_INIT_ERROR,
"Failed to init Controller:" + controller->Name());
......
......@@ -177,7 +177,7 @@ void UsbCam::mjpeg2rgb(char* mjpeg_buffer, int len, char* rgb_buffer,
video_sws_ =
sws_getContext(xsize, ysize, avcodec_context_->pix_fmt, xsize, ysize,
PIX_FMT_RGB24, SWS_BILINEAR, NULL, NULL, NULL);
PIX_FMT_RGB24, SWS_BILINEAR, nullptr, nullptr, nullptr);
sws_scale(video_sws_, avframe_camera_->data, avframe_camera_->linesize, 0,
ysize, avframe_rgb_->data, avframe_rgb_->linesize);
sws_freeContext(video_sws_);
......@@ -207,7 +207,7 @@ bool UsbCam::poll(const CameraImagePtr& raw_image) {
tv.tv_sec = 2;
tv.tv_usec = 0;
r = select(fd_ + 1, &fds, NULL, NULL, &tv);
r = select(fd_ + 1, &fds, nullptr, nullptr, &tv);
if (-1 == r) {
if (EINTR == errno) {
......@@ -891,7 +891,7 @@ bool UsbCam::read_frame(CameraImagePtr raw_image) {
}
bool UsbCam::process_image(const void* src, int len, CameraImagePtr dest) {
if (src == NULL || dest == NULL) {
if (src == nullptr || dest == nullptr) {
AERROR << "process image error. src or dest is null";
return false;
}
......@@ -977,7 +977,7 @@ void UsbCam::set_v4l_parameter(const std::string& param,
FILE* stream = popen(cmd.c_str(), "r");
if (stream) {
while (!feof(stream)) {
if (fgets(buffer, 256, stream) != NULL) {
if (fgets(buffer, 256, stream) != nullptr) {
output.append(buffer);
}
}
......
......@@ -101,7 +101,7 @@ int SocketInput::get_firing_data_packet(VelodynePacket *pkt) {
// socket using a blocking read.
uint8_t bytes[FIRING_DATA_PACKET_SIZE];
ssize_t nbytes =
recvfrom(sockfd_, bytes, FIRING_DATA_PACKET_SIZE, 0, NULL, NULL);
recvfrom(sockfd_, bytes, FIRING_DATA_PACKET_SIZE, 0, nullptr, nullptr);
if (nbytes < 0) {
if (errno != EWOULDBLOCK) {
......@@ -135,7 +135,8 @@ int SocketInput::get_positioning_data_packet(NMEATimePtr nmea_time) {
// Last 234 bytes not use
uint8_t bytes[POSITIONING_DATA_PACKET_SIZE];
ssize_t nbytes =
recvfrom(sockfd_, bytes, POSITIONING_DATA_PACKET_SIZE, 0, NULL, NULL);
recvfrom(sockfd_, bytes, POSITIONING_DATA_PACKET_SIZE, 0,
nullptr, nullptr);
if (nbytes < 0) {
if (errno != EWOULDBLOCK) {
......
......@@ -189,7 +189,7 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT> {
LeafConstPtr ret(&(leaf_iter->second));
return ret;
} else {
return NULL;
return nullptr;
}
}
......@@ -210,7 +210,7 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT> {
LeafConstPtr ret(&(leaf_iter->second));
return ret;
} else {
return NULL;
return nullptr;
}
}
......@@ -234,7 +234,7 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT> {
LeafConstPtr ret(&(leaf_iter->second));
return ret;
} else {
return NULL;
return nullptr;
}
}
......
......@@ -100,17 +100,17 @@ bool LRUCache<Key, Element>::Get(const Key &key, Element **value) {
template <class Key, class Element>
Element *LRUCache<Key, Element>::Put(const Key &key, Element *value) {
if (value == NULL) {
std::cout << "LRUCache Warning: put a NULL" << std::endl;
return NULL;
if (value == nullptr) {
std::cout << "LRUCache Warning: put a nullptr" << std::endl;
return nullptr;
}
Element *node_remove = NULL;
Element *node_remove = nullptr;
MapIterator found_iter = map_.find(key);
if (found_iter != map_.end()) {
// move the corresponding key to list front
list_.splice(list_.begin(), list_, found_iter->second);
node_remove = found_iter->second->second;
if (node_remove == value) return NULL;
if (node_remove == value) return nullptr;
if (Destroy(&node_remove)) {
found_iter->second->second = value;
} else {
......@@ -152,7 +152,7 @@ bool LRUCache<Key, Element>::IsExist(const Key &key) {
template <class Key, class Element>
Element *LRUCache<Key, Element>::Remove(const Key &key) {
Element *node_remove = NULL;
Element *node_remove = nullptr;
MapIterator found_iter = map_.find(key);
if (found_iter == map_.end()) {
......@@ -171,7 +171,7 @@ Element *LRUCache<Key, Element>::Remove(const Key &key) {
template <class Key, class Element>
Element *LRUCache<Key, Element>::ClearOne() {
// std::cout << "clear_one start" << std::endl;
Element *node_remove = NULL;
Element *node_remove = nullptr;
ListReverseIterator ritr = list_.rbegin();
while (ritr != list_.rend()) {
if (Destroy(&(ritr->second))) {
......
......@@ -68,7 +68,7 @@ BaseMapNode* BaseMapNodePool::AllocMapNode() {
boost::unique_lock<boost::mutex> lock(mutex_);
if (free_list_.empty()) {
if (is_fixed_size_) {
return NULL;
return nullptr;
}
BaseMapNode* node = AllocNewMapNode();
InitNewMapNode(node);
......
......@@ -50,7 +50,7 @@ LossyMapCell2D& LossyMapCell2D::operator=(const LossyMapCell2D& ref) {
LossyMapMatrix2D::LossyMapMatrix2D() {
rows_ = 0;
cols_ = 0;
map_cells_ = NULL;
map_cells_ = nullptr;
}
LossyMapMatrix2D::~LossyMapMatrix2D() {
......@@ -94,7 +94,7 @@ void LossyMapMatrix2D::Init(const BaseMapConfig* config) {
void LossyMapMatrix2D::Init(unsigned int rows, unsigned int cols) {
if (map_cells_) {
delete[] map_cells_;
map_cells_ = NULL;
map_cells_ = nullptr;
}
map_cells_ = new LossyMapCell2D[rows * cols];
rows_ = rows;
......
......@@ -141,8 +141,8 @@ TEST_F(LossyMap2DTestSuite, LossyMapToMapMatrixTest) {
for (; itr != buf.end(); ++itr, ++index) {
LossyMapNode* node =
static_cast<LossyMapNode*>(input_map.GetMapNodeSafe(*itr));
if (node == NULL) {
std::cerr << "index: " << index << " is a NULL pointer!" << std::endl;
if (node == nullptr) {
std::cerr << "index: " << index << " is a nullptr pointer!" << std::endl;
continue;
}
LossyMapMatrix& input_matrix =
......
......@@ -29,13 +29,13 @@ PCDExporter::PCDExporter(const std::string &pcd_folder) {
pcd_folder_ = pcd_folder;
std::string stamp_file = pcd_folder_ + "/pcd_timestamp.txt";
if ((stamp_file_handle_ = fopen(stamp_file.c_str(), "a")) == NULL) {
if ((stamp_file_handle_ = fopen(stamp_file.c_str(), "a")) == nullptr) {
AERROR << "Cannot open stamp file!";
}
}
PCDExporter::~PCDExporter() {
if (stamp_file_handle_ != NULL) {
if (stamp_file_handle_ != nullptr) {
fclose(stamp_file_handle_);
}
}
......
......@@ -32,7 +32,7 @@ namespace msf {
// ===================MessageBuffer=======================
template <class MessageType>
MessageBuffer<MessageType>::MessageBuffer(int capacity) : capacity_(capacity) {
pthread_mutex_init(&buffer_mutex_, NULL);
pthread_mutex_init(&buffer_mutex_, nullptr);
}
template <class MessageType>
......
......@@ -184,8 +184,8 @@ int main(int argc, char** argv) {
LosslessMapNode* lossless_node =
static_cast<LosslessMapNode*>(lossless_map.GetMapNodeSafe(*itr));
if (lossless_node == NULL) {
std::cerr << "index: " << index << " is a NULL pointer!" << std::endl;
if (lossless_node == nullptr) {
std::cerr << "index: " << index << " is a nullptr pointer!" << std::endl;
continue;
}
LosslessMapMatrix& lossless_matrix =
......
......@@ -26,12 +26,12 @@ CoordinateConvertTool::CoordinateConvertTool()
CoordinateConvertTool::~CoordinateConvertTool() {
if (pj_from_) {
pj_free(pj_from_);
pj_from_ = NULL;
pj_from_ = nullptr;
}
if (pj_to_) {
pj_free(pj_to_);
pj_to_ = NULL;
pj_to_ = nullptr;
}
}
......@@ -46,12 +46,12 @@ Status CoordinateConvertTool::SetConvertParam(const std::string &source_param,
dst_convert_param_ = dst_param;
if (pj_from_) {
pj_free(pj_from_);
pj_from_ = NULL;
pj_from_ = nullptr;
}
if (pj_to_) {
pj_free(pj_to_);
pj_to_ = NULL;
pj_to_ = nullptr;
}
if (!(pj_from_ = pj_init_plus(source_convert_param_.c_str()))) {
......@@ -62,7 +62,7 @@ Status CoordinateConvertTool::SetConvertParam(const std::string &source_param,
if (!(pj_to_ = pj_init_plus(dst_convert_param_.c_str()))) {
std::string err_msg = "Fail to pj_init_plus " + dst_convert_param_;
pj_free(pj_from_);
pj_from_ = NULL;
pj_from_ = nullptr;
return Status(apollo::common::ErrorCode::HDMAP_DATA_ERROR, err_msg);
}
......
......@@ -76,7 +76,7 @@ inline void SyncedMemory::to_cpu() {
break;
case HEAD_AT_GPU:
#ifndef PERCEPTION_CPU_ONLY
if (cpu_ptr_ == NULL) {
if (cpu_ptr_ == nullptr) {
PerceptionMallocHost(&cpu_ptr_, size_, cpu_malloc_use_cuda_);
own_cpu_data_ = true;
}
......@@ -103,7 +103,7 @@ inline void SyncedMemory::to_gpu() {
own_gpu_data_ = true;
break;
case HEAD_AT_CPU:
if (gpu_ptr_ == NULL) {
if (gpu_ptr_ == nullptr) {
BASE_CUDA_CHECK(cudaMalloc(&gpu_ptr_, size_));
own_gpu_data_ = true;
}
......@@ -143,7 +143,7 @@ const void* SyncedMemory::gpu_data() {
return (const void*)gpu_ptr_;
#else
NO_GPU;
return NULL;
return nullptr;
#endif
}
......@@ -177,7 +177,7 @@ void* SyncedMemory::mutable_gpu_data() {
return gpu_ptr_;
#else
NO_GPU;
return NULL;
return nullptr;
#endif
}
......@@ -185,7 +185,7 @@ void* SyncedMemory::mutable_gpu_data() {
void SyncedMemory::async_gpu_push(const cudaStream_t& stream) {
check_device();
CHECK_EQ(head_, HEAD_AT_CPU);
if (gpu_ptr_ == NULL) {
if (gpu_ptr_ == nullptr) {
BASE_CUDA_CHECK(cudaMalloc(&gpu_ptr_, size_));
own_gpu_data_ = true;
}
......
......@@ -35,12 +35,12 @@ Alignment power->alignment offset in bytes:
namespace idl {
template <typename T>
inline T *i_alloc(int memory_size) {
T *mem = NULL;
T *mem = nullptr;
if (!memory_size) {
return mem;
}
mem = new (std::nothrow) T[memory_size];
if (mem == NULL) {
if (mem == nullptr) {
return (NULL);
}
return (mem);
......@@ -48,9 +48,9 @@ inline T *i_alloc(int memory_size) {
template <typename T>
inline void i_free(T *&mem) {
if (mem != NULL) {
if (mem != nullptr) {
delete[] mem;
mem = NULL;
mem = nullptr;
}
}
......@@ -59,11 +59,11 @@ template <typename T>
inline T **i_alloc2(int m, int n) {
T *mem, **head;
mem = new (std::nothrow) T[m * n];
if (mem == NULL) {
if (mem == nullptr) {
return (NULL);
}
head = new (std::nothrow) T *[m];
if (head == NULL) {
if (head == nullptr) {
delete[] mem;
return (NULL);
}
......@@ -74,10 +74,10 @@ inline T **i_alloc2(int m, int n) {
/*Free memory allocated with function i_alloc2*/
template <typename T>
inline void i_free2(T **&A) {
if (A != NULL) {
if (A != nullptr) {
delete[] A[0];
delete[] A;
A = NULL;
A = nullptr;
}
}
......@@ -87,17 +87,17 @@ inline T ***i_alloc3(int l, int m, int n) {
T *mem, ***head;
int i, j;
mem = new (std::nothrow) T[l * m * n];
if (mem == NULL) {
if (mem == nullptr) {
return (NULL);
}
head = new (std::nothrow) T **[l];
if (head == NULL) {
if (head == nullptr) {
delete[] mem;
return (NULL);
}
for (i = 0; i < l; i++) {
head[i] = new (std::nothrow) T *[m];
if (head[i] == NULL) {
if (head[i] == nullptr) {
for (j = 0; j < i; j++) delete[] head[j];
delete[] head;
delete[] mem;
......@@ -110,11 +110,11 @@ inline T ***i_alloc3(int l, int m, int n) {
template <class T>
inline void i_free3(T ***&A, int l) {
if (A != NULL) {
if (A != nullptr) {
delete[](A[0][0]);
for (int i = 0; i < l; i++) delete[] A[i];
delete[] A;
A = NULL;
A = nullptr;
}
}
......@@ -145,7 +145,7 @@ template <typename T>
inline void i_free_aligned(T *&mem) {
if (mem) {
delete[]((char **)mem)[-1];
mem = NULL;
mem = nullptr;
}
}
......
......@@ -4372,7 +4372,7 @@ inline void i_mult_Ax(const T *A, const T *x, T *Ax, int m, int n) {
template <typename T>
inline void i_mult_Atx(const T *A, const T *x, T *Atx, int m, int n) {
T acc;
const T *Ai = NULL;
const T *Ai = nullptr;
for (int i = 0; i < n; i++) {
Ai = A + i;
acc = T(0.0);
......
......@@ -221,10 +221,10 @@ inline void i_plane_fit_total_least_square(
const T* X, T pi[4], int n, T* Xp, T centroid[3],
T err_stat[2] /*mean err and err std*/) {
i_zero4(pi);
if (centroid != NULL) {
if (centroid != nullptr) {
i_zero3(centroid);
}
if (err_stat != NULL) {
if (err_stat != nullptr) {
i_zero2(err_stat);
}
if (n < 3) {
......@@ -259,12 +259,12 @@ inline void i_plane_fit_total_least_square(
/*the optimal plane should pass [xm, ym, zm]:*/
pi[3] = -i_dot3(pi, t);
if (centroid != NULL) {
if (centroid != nullptr) {
i_copy3(t, centroid);
}
/*data stat:*/
if (err_stat != NULL) {
if (err_stat != nullptr) {
const T* cptr_data = X;
for (i = 0; i < n; ++i) {
Xp[i] = i_plane_to_point_distance(pi, cptr_data);
......@@ -423,7 +423,7 @@ inline void i_plane_fit_total_least_square(T* X, int* indices, T pi[4],
/*the optimal plane should pass [xm, ym, zm]:*/
pi[3] = -(pi[0] * xm + pi[1] * ym + pi[2] * zm);
if (centroid != NULL) {
if (centroid != nullptr) {
centroid[0] = xm;
centroid[1] = ym;
centroid[2] = zm;
......
......@@ -139,7 +139,7 @@ bool PlaneFitGroundDetector::init() {
}
// fine grid:
_vg_fine = new VoxelGridXY<float>();
if (_vg_fine == NULL) {
if (_vg_fine == nullptr) {
return false;
}
if (!_vg_fine->alloc(_param.nr_grids_fine, _param.nr_grids_fine,
......@@ -150,7 +150,7 @@ bool PlaneFitGroundDetector::init() {
}
// coarse grid:
_vg_coarse = new VoxelGridXY<float>();
if (_vg_coarse == NULL) {
if (_vg_coarse == nullptr) {
return false;
}
if (!_vg_coarse->alloc(_param.nr_grids_coarse, _param.nr_grids_coarse,
......@@ -288,7 +288,7 @@ int PlaneFitGroundDetector::compare_z(const float *point_cloud,
unsigned int nr_contradi = 0;
unsigned int nr_z_comp_fail_threshold =
i_min(_param.nr_z_comp_fail_threshold, (unsigned int)(nr_compares >> 1));
const float *ptr = NULL;
const float *ptr = nullptr;
float z = 0;
float delta_z = 0;
std::vector<int>::const_iterator iter = indices.cbegin();
......@@ -411,36 +411,36 @@ void PlaneFitGroundDetector::compute_signed_ground_height_line(
unsigned int id = 0;
int pos = 0;
char label = 0;
const float *cptr = NULL;
const float *cptr = nullptr;
float dist[] = {0, 0, 0, 0, 0};
const float *plane[] = {NULL, NULL, NULL, NULL, NULL};
const float *plane[] = {NULL, nullptr, nullptr, nullptr, nullptr};
float min_abs_dist = 0;
unsigned int nm1 = _param.nr_grids_coarse - 1;
CHECK_GE(_param.nr_grids_coarse, 2);
plane[0] = cn[0].is_valid() ? cn[0].params : NULL;
plane[1] = cn[1].is_valid() ? cn[1].params : NULL;
plane[2] = up[0].is_valid() ? up[0].params : NULL;
plane[3] = dn[0].is_valid() ? dn[0].params : NULL;
plane[0] = cn[0].is_valid() ? cn[0].params : nullptr;
plane[1] = cn[1].is_valid() ? cn[1].params : nullptr;
plane[2] = up[0].is_valid() ? up[0].params : nullptr;
plane[3] = dn[0].is_valid() ? dn[0].params : nullptr;
std::vector<int>::const_iterator iter = (*_vg_coarse)(r, 0)._indices.cbegin();
while (iter < (*_vg_coarse)(r, 0)._indices.cend()) {
pos = *iter;
CHECK_LT(pos, (int)nr_points);
label = _labels[pos];
cptr = point_cloud + (nr_point_elements * pos);
dist[0] = plane[0] != NULL
dist[0] = plane[0] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[0], cptr)
: FLT_MAX;
min_abs_dist = i_abs(dist[0]);
id = 0;
// for candidates we take min dist:
if (label) {
dist[1] = plane[1] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[1] = plane[1] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[1], cptr)
: FLT_MAX;
dist[2] = plane[2] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[2] = plane[2] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[2], cptr)
: FLT_MAX;
dist[3] = plane[3] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[3] = plane[3] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[3], cptr)
: FLT_MAX;
for (i = 1; i < 4; ++i) {
......@@ -455,37 +455,37 @@ void PlaneFitGroundDetector::compute_signed_ground_height_line(
}
for (c = 1; c < nm1; ++c) {
plane[0] = cn[c].is_valid() ? cn[c].params : NULL;
plane[1] = cn[c - 1].is_valid() ? cn[c - 1].params : NULL;
plane[2] = cn[c + 1].is_valid() ? cn[c + 1].params : NULL;
plane[3] = up[c].is_valid() ? up[c].params : NULL;
plane[4] = dn[c].is_valid() ? dn[c].params : NULL;
plane[0] = cn[c].is_valid() ? cn[c].params : nullptr;
plane[1] = cn[c - 1].is_valid() ? cn[c - 1].params : nullptr;
plane[2] = cn[c + 1].is_valid() ? cn[c + 1].params : nullptr;
plane[3] = up[c].is_valid() ? up[c].params : nullptr;
plane[4] = dn[c].is_valid() ? dn[c].params : nullptr;
iter = (*_vg_coarse)(r, c)._indices.cbegin();
while (iter < (*_vg_coarse)(r, c)._indices.cend()) {
pos = *iter;
CHECK_LT(pos, (int)nr_points);
label = _labels[pos];
cptr = point_cloud + (nr_point_elements * pos);
dist[0] = plane[0] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[0] = plane[0] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[0], cptr)
: FLT_MAX;
min_abs_dist = i_abs(dist[0]);
id = 0;
if (label) {
dist[1] =
plane[1] != NULL
plane[1] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[1], cptr)
: FLT_MAX;
dist[2] =
plane[2] != NULL
plane[2] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[2], cptr)
: FLT_MAX;
dist[3] =
plane[3] != NULL
plane[3] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[3], cptr)
: FLT_MAX;
dist[4] =
plane[4] != NULL
plane[4] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[4], cptr)
: FLT_MAX;
for (i = 1; i < 5; ++i) {
......@@ -499,30 +499,30 @@ void PlaneFitGroundDetector::compute_signed_ground_height_line(
++iter;
}
}
plane[0] = cn[nm1].is_valid() ? cn[nm1].params : NULL;
plane[1] = cn[nm1 - 1].is_valid() ? cn[nm1 - 1].params : NULL;
plane[2] = up[nm1].is_valid() ? up[nm1].params : NULL;
plane[3] = dn[nm1].is_valid() ? dn[nm1].params : NULL;
plane[0] = cn[nm1].is_valid() ? cn[nm1].params : nullptr;
plane[1] = cn[nm1 - 1].is_valid() ? cn[nm1 - 1].params : nullptr;
plane[2] = up[nm1].is_valid() ? up[nm1].params : nullptr;
plane[3] = dn[nm1].is_valid() ? dn[nm1].params : nullptr;
iter = (*_vg_coarse)(r, nm1)._indices.cbegin();
while (iter < (*_vg_coarse)(r, nm1)._indices.cend()) {
pos = *iter;
CHECK_LT(pos, (int)nr_points);
label = _labels[pos];
cptr = point_cloud + (nr_point_elements * pos);
dist[0] = plane[0] != NULL
dist[0] = plane[0] != nullptr
? i_plane_to_point_signed_distance_w_unit_norm(plane[0], cptr)
: FLT_MAX;
min_abs_dist = i_abs(dist[0]);
id = 0;
// for candidates we take min dist:
if (label) {
dist[1] = plane[1] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[1] = plane[1] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[1], cptr)
: FLT_MAX;
dist[2] = plane[2] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[2] = plane[2] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[2], cptr)
: FLT_MAX;
dist[3] = plane[3] != NULL ? i_plane_to_point_signed_distance_w_unit_norm(
dist[3] = plane[3] != nullptr ? i_plane_to_point_signed_distance_w_unit_norm(
plane[3], cptr)
: FLT_MAX;
for (i = 1; i < 4; ++i) {
......@@ -637,7 +637,7 @@ int PlaneFitGroundDetector::fit_grid(const float *point_cloud,
// 3x3 matrix stores: x, y, z; x, y, z; x, y, z;
float samples[9];
// copy 3D points
float *psrc = NULL;
float *psrc = nullptr;
float *pdst = _pf_threeds;
for (i = 0; i < nr_samples; ++i) {
CHECK_LT(candi[i], (int)nr_points);
......@@ -837,7 +837,7 @@ int PlaneFitGroundDetector::fit_grid_with_neighbors(
// 3x3 matrix stores: x, y, z; x, y, z; x, y, z;
float samples[9];
// copy 3D points
float *psrc = NULL;
float *psrc = nullptr;
float *pdst = _pf_threeds;
int r_n = 0;
int c_n = 0;
......@@ -1271,7 +1271,7 @@ const GroundPlaneLiDAR *PlaneFitGroundDetector::get_ground_plane(int r,
CHECK_LT(r, (int)_param.nr_grids_coarse);
CHECK_GE(c, 0);
CHECK_LT(c, (int)_param.nr_grids_coarse);
return _ground_planes != NULL ? _ground_planes[r] + c : NULL;
return _ground_planes != nullptr ? _ground_planes[r] + c : nullptr;
}
const unsigned int PlaneFitGroundDetector::get_grid_dim_x() const {
......
......@@ -58,7 +58,7 @@ class PtCluster {
if (c.nr_points()) {
_nr_points = c.nr_points();
_data = i_alloc_aligned<T>(_nr_points * d, 4);
CHECK_NE(_data, NULL);
CHECK_NE(_data, nullptr);
CHECK(i_verify_alignment(_data, 4));
i_copy(c.const_data(), _data, _nr_points * d);
}
......@@ -69,7 +69,7 @@ class PtCluster {
if (this->_nr_points != c.nr_points()) {
i_free_aligned(_data);
_data = i_alloc_aligned<T>(this->_nr_points * d, 4);
CHECK_NE(_data, NULL);
CHECK_NE(_data, nullptr);
CHECK(i_verify_alignment(_data, 4));
this->_nr_points = c.nr_points();
}
......@@ -496,7 +496,7 @@ VoxelGridXY<T>::VoxelGridXY()
template <typename T>
void VoxelGridXY<T>::cleanup() {
_initialized = false;
_data = NULL;
_data = nullptr;
_nr_points = _nr_point_element = _nr_voxel_x = _nr_voxel_y = 0;
_nr_voxel_z = 1;
i_zero2(_dim_x);
......@@ -573,7 +573,7 @@ bool VoxelGridXY<T>::alloc_aligned_memory() {
if (!_mem_aligned16_i32) {
_mem_aligned16_i32 = i_alloc_aligned<int>(4, 4);
}
return (_mem_aligned16_f32 != NULL && _mem_aligned16_i32 != NULL &&
return (_mem_aligned16_f32 != nullptr && _mem_aligned16_i32 != nullptr &&
i_verify_alignment(_mem_aligned16_f32, 4) &&
i_verify_alignment(_mem_aligned16_i32, 4));
}
......@@ -1438,7 +1438,7 @@ bool VoxelGridXYPyramid<DATA_TYPE>::set(
template <typename DATA_TYPE>
void VoxelGridXYPyramid<DATA_TYPE>::cleanup() {
_pc = NULL;
_pc = nullptr;
_vgrids.clear();
_nr_points = _nr_point_element = _dsf_x = _dsf_y = _dsf_z = 0;
}
......
......@@ -44,7 +44,7 @@ TEST(HoughTransferTest, image_no_line_test) {
EXPECT_EQ(0, lines.size());
// nullptr
transfer.ImageVote(image, true);
transfer.GetLines(4, 1, 1, true, NULL);
transfer.GetLines(4, 1, 1, true, nullptr);
EXPECT_EQ(0, lines.size());
// wrong input
flag = transfer.Init(0, 1, 1.0, 1.0);
......
......@@ -30,7 +30,7 @@ int KalmanMotionFusion::s_eval_window_ = 3;
size_t KalmanMotionFusion::s_history_size_maximum_ = 20;
bool KalmanMotionFusion::Init() {
if (track_ref_ == NULL) {
if (track_ref_ == nullptr) {
return false;
}
if (track_ref_->GetLatestLidarObject() != nullptr) {
......
......@@ -29,7 +29,7 @@ namespace inference {
BatchStream::BatchStream(int batchSize, int maxBatches, std::string dataPath)
: mBatchSize(batchSize), mMaxBatches(maxBatches), mPath(dataPath) {
FILE *file = fopen((mPath + "Batch0").c_str(), "rb");
if (file != NULL) {
if (file != nullptr) {
int d[4];
int fs = fread(d, sizeof(int), 4, file);
CHECK_EQ(fs, 4);
......@@ -94,7 +94,7 @@ void BatchStream::skip(int skipCount) {
bool BatchStream::update() {
std::string inputFileName = mPath + "Batch" + std::to_string(mFileCount++);
FILE *file = fopen(inputFileName.c_str(), "rb");
if (file == NULL) {
if (file == nullptr) {
return false;
}
......
......@@ -72,7 +72,7 @@ void RTNet::addConvLayer(const LayerParameter &layer_param,
ConvolutionParameter conv = layer_param.convolution_param();
ConvParam param;
CHECK(ParserConvParam(conv, &param));
nvinfer1::IConvolutionLayer *convLayer = NULL;
nvinfer1::IConvolutionLayer *convLayer = nullptr;
int size = conv.num_output() * param.kernel_w * param.kernel_h *
inputs[0]->getDimensions().d[0];
......@@ -125,7 +125,7 @@ void RTNet::addDeconvLayer(const LayerParameter &layer_param,
ConvolutionParameter conv = layer_param.convolution_param();
ConvParam param;
ParserConvParam(conv, &param);
nvinfer1::IDeconvolutionLayer *deconvLayer = NULL;
nvinfer1::IDeconvolutionLayer *deconvLayer = nullptr;
if ((*weight_map)[layer_param.name().c_str()].size() == 2) {
deconvLayer =
net->addDeconvolution(*inputs[0], conv.num_output(),
......
......@@ -19,7 +19,7 @@
// get_instance();
//
// string model_name = "FrameClassifier";
// const ModelConfig* model_config = NULL;
// const ModelConfig* model_config = nullptr;
// if (!config_manager->GetModelConfig(model_name, &model_config)) {
// AERROR << "not found model: " << model_name;
// return false;
......
......@@ -36,7 +36,7 @@ class ConfigManagerTest : public testing::Test {
putenv(module_path);
FLAGS_config_manager_path = "/apollo/modules/perception/testdata/lib/conf";
config_manager_ = lib::Singleton<ConfigManager>::get_instance();
ASSERT_TRUE(config_manager_ != NULL);
ASSERT_TRUE(config_manager_ != nullptr);
}
protected:
......@@ -62,21 +62,21 @@ TEST_F(ConfigManagerTest, TestInit) {
TEST_F(ConfigManagerTest, TestGetModelConfig) {
std::string model_name = "FrameClassifier";
const ModelConfig* model_config = NULL;
const ModelConfig* model_config = nullptr;
EXPECT_TRUE(config_manager_->GetModelConfig(model_name, &model_config));
ASSERT_TRUE(model_config != NULL);
ASSERT_TRUE(model_config != nullptr);
EXPECT_EQ(model_config->name(), model_name);
// not exist model.
model_config = NULL;
model_config = nullptr;
EXPECT_FALSE(config_manager_->GetModelConfig("noexist", &model_config));
EXPECT_TRUE(model_config == NULL);
EXPECT_TRUE(model_config == nullptr);
}
TEST_F(ConfigManagerTest, TestModelConfig) {
std::string model_name = "FrameClassifier";
const ModelConfig* model_config = NULL;
const ModelConfig* model_config = nullptr;
ASSERT_TRUE(config_manager_->Init());
ASSERT_EQ(config_manager_->NumModels(), 2u);
ASSERT_FALSE(
......
......@@ -75,12 +75,12 @@ bool FileUtil::DeleteFile(const string &filename) {
// directory,remove iteratively
DIR *dir = opendir(filename.c_str());
if (dir == NULL) {
if (dir == nullptr) {
AWARN << "failed to opendir: " << filename;
return false;
}
dirent *dir_info = NULL;
while ((dir_info = readdir(dir)) != NULL) {
dirent *dir_info = nullptr;
while ((dir_info = readdir(dir)) != nullptr) {
if (strcmp(dir_info->d_name, ".") == 0 ||
strcmp(dir_info->d_name, "..") == 0) {
continue;
......@@ -166,7 +166,7 @@ bool FileUtil::CreateDir(const string &dir) {
}
bool FileUtil::GetFileContent(const string &path, string *content) {
if (content == NULL) {
if (content == nullptr) {
return false;
}
......
......@@ -184,7 +184,7 @@ TEST(FileUtilTest, TestRenameFile) {
TEST(FileUtilTest, TestGetFileContent) {
std::string path = "/apollo/modules/perception/testdata/lib/data/1.txt";
std::string content;
EXPECT_FALSE(FileUtil::GetFileContent(path, NULL));
EXPECT_FALSE(FileUtil::GetFileContent(path, nullptr));
EXPECT_FALSE(FileUtil::GetFileContent(
"/apollo/modules/perception/testdata/lib/data/2.txt", &content));
EXPECT_TRUE(FileUtil::GetFileContent(path, &content));
......
......@@ -37,14 +37,14 @@ class Any {
: content_(new Holder<ValueType>(value)) {}
Any(const Any &other)
: content_(other.content_ ? other.content_->Clone() : NULL) {}
: content_(other.content_ ? other.content_->Clone() : nullptr) {}
~Any() { delete content_; }
template <typename ValueType>
ValueType *AnyCast() {
return content_ ? &(static_cast<Holder<ValueType> *>(content_)->held_)
: NULL; // NOLINT
: nullptr; // NOLINT
}
private:
......@@ -105,7 +105,7 @@ bool GetRegisteredClasses(
AERROR << "Instance:" << c.first; \
} \
AERROR << "Get instance " << name << " failed."; \
return NULL; \
return nullptr; \
} \
Any object = iter->second->NewInstance(); \
return *(object.AnyCast<base_class *>()); \
......
......@@ -56,7 +56,7 @@ template <typename T>
pthread_once_t Singleton<T>::p_once_ = PTHREAD_ONCE_INIT;
template <typename T>
T *Singleton<T>::instance_ = NULL;
T *Singleton<T>::instance_ = nullptr;
} // namespace lib
} // namespace perception
......
......@@ -24,7 +24,7 @@ namespace lib {
class Mutex {
public:
Mutex() { pthread_mutex_init(&mu_, NULL); }
Mutex() { pthread_mutex_init(&mu_, nullptr); }
~Mutex() { pthread_mutex_destroy(&mu_); }
......@@ -57,7 +57,7 @@ class MutexLock {
// Wrapper for pthread_cond_t
class CondVar {
public:
CondVar() { pthread_cond_init(&cv_, NULL); }
CondVar() { pthread_cond_init(&cv_, nullptr); }
~CondVar() { pthread_cond_destroy(&cv_); }
void Wait(Mutex *mu) { pthread_cond_wait(&cv_, &mu->mu_); }
......@@ -112,7 +112,7 @@ class BlockingCounter {
class RwMutex {
public:
RwMutex() { pthread_rwlock_init(&mu_, NULL); }
RwMutex() { pthread_rwlock_init(&mu_, nullptr); }
~RwMutex() { pthread_rwlock_destroy(&mu_); }
inline void ReaderLock() { pthread_rwlock_rdlock(&mu_); }
......
......@@ -30,8 +30,8 @@ void Thread::Start() {
pthread_attr_setdetachstate(
&attr, joinable_ ? PTHREAD_CREATE_JOINABLE : PTHREAD_CREATE_DETACHED),
0);
CHECK_EQ(pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, NULL), 0);
CHECK_EQ(pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL), 0);
CHECK_EQ(pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, nullptr), 0);
CHECK_EQ(pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, nullptr), 0);
int result = pthread_create(&tid_, &attr, &ThreadRunner, this);
CHECK_EQ(result, 0) << "Could not create thread (" << result << ")";
......@@ -43,7 +43,7 @@ void Thread::Start() {
void Thread::Join() {
CHECK(joinable_) << "Thread is not joinable";
int result = pthread_join(tid_, NULL);
int result = pthread_join(tid_, nullptr);
CHECK_EQ(result, 0) << "Could not join thread (" << tid_ << ", "
<< thread_name_ << ")";
tid_ = 0;
......
......@@ -54,7 +54,7 @@ class Thread {
static void *ThreadRunner(void *arg) {
Thread *t = reinterpret_cast<Thread *>(arg);
t->Run();
return NULL;
return nullptr;
}
pthread_t tid_;
......
......@@ -70,9 +70,9 @@ void ThreadPool::Add(const vector<Closure *> &closures) {
void ThreadPoolWorker::Run() {
while (true) {
Closure *closure = NULL;
Closure *closure = nullptr;
thread_pool_->task_queue_.Pop(&closure);
if (closure == NULL) {
if (closure == nullptr) {
break;
}
......
......@@ -27,14 +27,14 @@ using std::string;
void Timer::Start() {
struct timeval tv;
gettimeofday(&tv, NULL);
gettimeofday(&tv, nullptr);
start_time_ = tv.tv_sec * 1000 + tv.tv_usec / 1000;
}
uint64_t Timer::End(const string &msg) {
struct timeval tv;
gettimeofday(&tv, NULL);
gettimeofday(&tv, nullptr);
end_time_ = tv.tv_sec * 1000 + tv.tv_usec / 1000;
uint64_t elapsed_time = end_time_ - start_time_;
......
......@@ -58,7 +58,7 @@ bool GroundServiceDetector::Init(const GroundDetectorInitOptions& options) {
bool GroundServiceDetector::Detect(const GroundDetectorOptions& options,
LidarFrame* frame) {
if (frame == NULL || frame->world_cloud == nullptr) {
if (frame == nullptr || frame->world_cloud == nullptr) {
AERROR << "Frame is nullptr.";
return false;
}
......
......@@ -96,7 +96,7 @@ TEST_F(LidarLibGroundServiceDetectorTest,
EXPECT_TRUE(SceneManager::Instance().Init());
EXPECT_TRUE(ground_service_detector.Init(GroundDetectorInitOptions()));
EXPECT_FALSE(ground_service_detector.Detect(GroundDetectorOptions(), NULL));
EXPECT_FALSE(ground_service_detector.Detect(GroundDetectorOptions(), nullptr));
LidarFrame frame;
EXPECT_FALSE(ground_service_detector.Detect(GroundDetectorOptions(), &frame));
frame.world_cloud = base::PointDCloudPool::Instance().Get();
......
......@@ -35,7 +35,7 @@ bool ROIServiceFilter::Init(const ROIFilterInitOptions& options) {
bool ROIServiceFilter::Filter(const ROIFilterOptions& options,
LidarFrame* frame) {
if (frame == NULL || frame->world_cloud == nullptr) {
if (frame == nullptr || frame->world_cloud == nullptr) {
AERROR << "Frame is nullptr.";
return false;
}
......
......@@ -111,7 +111,7 @@ TEST_F(LidarLibROIServiceFilterTest, lidar_lib_roi_service_filter_test) {
EXPECT_TRUE(SceneManager::Instance().Init());
EXPECT_TRUE(roi_service_filter.Init(ROIFilterInitOptions()));
EXPECT_FALSE(roi_service_filter.Filter(ROIFilterOptions(), NULL));
EXPECT_FALSE(roi_service_filter.Filter(ROIFilterOptions(), nullptr));
LidarFrame frame;
EXPECT_FALSE(roi_service_filter.Filter(ROIFilterOptions(), &frame));
MockData(&frame);
......
......@@ -60,7 +60,7 @@ class OfflineLidarObstaclePerception {
bool setup() {
FLAGS_config_manager_path = "./conf";
config_manager_ = lib::Singleton<lib::ConfigManager>::get_instance();
if (config_manager_ == NULL) {
if (config_manager_ == nullptr) {
AERROR << "Failed to get ConfigManager instance.";
return false;
}
......
......@@ -78,7 +78,7 @@ bool HDMapInput::InitHDMap() {
lib::Singleton<ConfigManager>::get_instance();
CHECK_NOTNULL(config_manager);
std::string model_name = "HDMapInput";
const lib::ModelConfig* model_config = NULL;
const lib::ModelConfig* model_config = nullptr;
if (!config_manager->GetModelConfig(model_name, &model_config)) {
AERROR << "not found model: " << model_name;
return false;
......
......@@ -41,7 +41,7 @@ class HDMapInputTest : public testing::Test {
// FLAGS_config_manager_path = "/apollo/modules/perception/testdata/"
// "map/hdmap/conf";
// config_manager_ = lib::Singleton<ConfigManager>::get_instance();
// ASSERT_TRUE(config_manager_ != NULL);
// ASSERT_TRUE(config_manager_ != nullptr);
}
protected:
......
......@@ -240,7 +240,7 @@ bool LateralTrajectoryOptimizerInterface::eval_jac_g(int n, const double* x,
auto offset_prime = num_of_points_;
auto offset_pprime = 2 * num_of_points_;
if (values == NULL) {
if (values == nullptr) {
std::size_t nz_index = 0;
std::size_t constraint_index = 0;
......
......@@ -65,15 +65,15 @@ class LateralTrajectoryOptimizerInterface : public Ipopt::TNLP {
bool eval_g(int n, const double* x, bool new_x, int m, double* g) override;
/** Method to return:
* 1) The structure of the jacobian (if "values" is NULL)
* 2) The values of the jacobian (if "values" is not NULL)
* 1) The structure of the jacobian (if "values" is nullptr)
* 2) The values of the jacobian (if "values" is not nullptr)
*/
bool eval_jac_g(int n, const double* x, bool new_x, int m, int nele_jac,
int* iRow, int* jCol, double* values) override;
/** Method to return:
* 1) The structure of the hessian of the lagrangian (if "values" is NULL)
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
* 1) The structure of the hessian of the lagrangian (if "values" is nullptr)
* 2) The values of the hessian of the lagrangian (if "values" is not nullptr)
*/
bool eval_h(int n, const double* x, bool new_x, double obj_factor, int m,
const double* lambda, bool new_lambda, int nele_hess, int* iRow,
......
......@@ -75,15 +75,15 @@ class DistanceApproachIPOPTInterface : public Ipopt::TNLP {
bool eval_g(int n, const double* x, bool new_x, int m, double* g) override;
/** Method to return:
* 1) The structure of the jacobian (if "values" is NULL)
* 2) The values of the jacobian (if "values" is not NULL)
* 1) The structure of the jacobian (if "values" is nullptr)
* 2) The values of the jacobian (if "values" is not nullptr)
*/
bool eval_jac_g(int n, const double* x, bool new_x, int m, int nele_jac,
int* iRow, int* jCol, double* values) override;
/** Method to return:
* 1) The structure of the hessian of the lagrangian (if "values" is NULL)
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
* 1) The structure of the hessian of the lagrangian (if "values" is nullptr)
* 2) The values of the hessian of the lagrangian (if "values" is not nullptr)
*/
bool eval_h(int n, const double* x, bool new_x, double obj_factor, int m,
const double* lambda, bool new_lambda, int nele_hess, int* iRow,
......
......@@ -69,15 +69,15 @@ class WarmStartIPOPTInterface : public Ipopt::TNLP {
bool eval_g(int n, const double* x, bool new_x, int m, double* g) override;
/** Method to return:
* 1) The structure of the jacobian (if "values" is NULL)
* 2) The values of the jacobian (if "values" is not NULL)
* 1) The structure of the jacobian (if "values" is nullptr)
* 2) The values of the jacobian (if "values" is not nullptr)
*/
bool eval_jac_g(int n, const double* x, bool new_x, int m, int nele_jac,
int* iRow, int* jCol, double* values) override;
/** Method to return:
* 1) The structure of the hessian of the lagrangian (if "values" is NULL)
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
* 1) The structure of the hessian of the lagrangian (if "values" is nullptr)
* 2) The values of the hessian of the lagrangian (if "values" is not nullptr)
*/
bool eval_h(int n, const double* x, bool new_x, double obj_factor, int m,
const double* lambda, bool new_lambda, int nele_hess, int* iRow,
......
......@@ -268,7 +268,7 @@ bool CosThetaProbleminterface::eval_jac_g(int n, const double* x, bool new_x,
int* jCol, double* values) {
CHECK_EQ(static_cast<std::size_t>(n), num_of_variables_);
CHECK_EQ(static_cast<std::size_t>(m), num_of_constraints_);
if (values == NULL) {
if (values == nullptr) {
// positional deviation constraints
for (std::size_t i = 0; i < num_of_variables_; ++i) {
iRow[i] = i;
......@@ -289,7 +289,7 @@ bool CosThetaProbleminterface::eval_h(int n, const double* x, bool new_x,
const double* lambda, bool new_lambda,
int nele_hess, int* iRow, int* jCol,
double* values) {
if (values == NULL) {
if (values == nullptr) {
std::size_t index = 0;
for (std::size_t i = 0; i < 6; ++i) {
for (std::size_t j = 0; j <= i; ++j) {
......
......@@ -76,15 +76,15 @@ class CosThetaProbleminterface : public Ipopt::TNLP {
bool eval_g(int n, const double* x, bool new_x, int m, double* g) override;
/** Method to return:
* 1) The structure of the jacobian (if "values" is NULL)
* 2) The values of the jacobian (if "values" is not NULL)
* 1) The structure of the jacobian (if "values" is nullptr)
* 2) The values of the jacobian (if "values" is not nullptr)
*/
bool eval_jac_g(int n, const double* x, bool new_x, int m, int nele_jac,
int* iRow, int* jCol, double* values) override;
/** Method to return:
* 1) The structure of the hessian of the lagrangian (if "values" is NULL)
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
* 1) The structure of the hessian of the lagrangian (if "values" is nullptr)
* 2) The values of the hessian of the lagrangian (if "values" is not nullptr)
*/
bool eval_h(int n, const double* x, bool new_x, double obj_factor, int m,
const double* lambda, bool new_lambda, int nele_hess, int* iRow,
......
......@@ -435,7 +435,7 @@ bool SpiralProblemInterface::eval_jac_g(int n, const double* x, bool new_x,
CHECK_EQ(std::size_t(n), num_of_variables_);
CHECK_EQ(std::size_t(m), num_of_constraints_);
if (values == NULL) {
if (values == nullptr) {
std::size_t nz_index = 0;
std::size_t variable_offset = num_of_points_ * 5;
......@@ -676,7 +676,7 @@ bool SpiralProblemInterface::eval_h(int n, const double* x, bool new_x,
const double* lambda, bool new_lambda,
int nele_hess, int* iRow, int* jCol,
double* values) {
if (values == NULL) {
if (values == nullptr) {
std::size_t index = 0;
for (std::size_t i = 0; i + 1 < num_of_points_; ++i) {
std::size_t variable_index = i * 5;
......
......@@ -85,15 +85,15 @@ class SpiralProblemInterface : public Ipopt::TNLP {
bool eval_g(int n, const double* x, bool new_x, int m, double* g) override;
/** Method to return:
* 1) The structure of the jacobian (if "values" is NULL)
* 2) The values of the jacobian (if "values" is not NULL)
* 1) The structure of the jacobian (if "values" is nullptr)
* 2) The values of the jacobian (if "values" is not nullptr)
*/
bool eval_jac_g(int n, const double* x, bool new_x, int m, int nele_jac,
int* iRow, int* jCol, double* values) override;
/** Method to return:
* 1) The structure of the hessian of the lagrangian (if "values" is NULL)
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
* 1) The structure of the hessian of the lagrangian (if "values" is nullptr)
* 2) The values of the hessian of the lagrangian (if "values" is not nullptr)
*/
bool eval_h(int n, const double* x, bool new_x, double obj_factor, int m,
const double* lambda, bool new_lambda, int nele_hess, int* iRow,
......
......@@ -90,14 +90,14 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
* \param target_time The time at which to transform
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
const std::string& source_frame,
const cybertron::Time& target_time,
const float timeout_second = 0.01,
std::string* errstr = NULL) const;
std::string* errstr = nullptr) const;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
......@@ -108,7 +108,7 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
* time
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
......@@ -117,7 +117,7 @@ class Buffer : public BufferInterface, public tf2::BufferCore {
const cybertron::Time& source_time,
const std::string& fixed_frame,
const float timeout_second = 0.01,
std::string* errstr = NULL) const;
std::string* errstr = nullptr) const;
private:
void SubscriptionCallback(
......
......@@ -77,14 +77,14 @@ class BufferInterface {
* \param time The time at which to transform
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
const std::string& source_frame,
const cybertron::Time& time,
const float timeout_second = 0.01,
std::string* errstr = NULL) const = 0;
std::string* errstr = nullptr) const = 0;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
......@@ -95,7 +95,7 @@ class BufferInterface {
* time
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the
* transform failed, if not NULL
* transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
virtual bool canTransform(const std::string& target_frame,
......@@ -104,7 +104,7 @@ class BufferInterface {
const cybertron::Time& source_time,
const std::string& fixed_frame,
const float timeout_second = 0.01,
std::string* errstr = NULL) const = 0;
std::string* errstr = nullptr) const = 0;
// Transform, simple api, with pre-allocation
template <typename T>
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册