提交 b54e8842 编写于 作者: Z Zhang Liangliang 提交者: Jiangtao Hu

Localization: code clean.

上级 15067aff
......@@ -15,10 +15,12 @@
*****************************************************************************/
#include "modules/localization/msf/common/util/compression.h"
#include <assert.h>
#include <zlib.h>
#include <cstdio>
#include "modules/common/log.h"
namespace apollo {
namespace localization {
namespace msf {
......@@ -69,7 +71,7 @@ unsigned int ZlibStrategy::ZlibCompress(BufferStr* src, BufferStr* dst) {
stream_data.avail_out = zlib_chunk;
stream_data.next_out = out;
ret = deflate(&stream_data, flush); /* no bad return value */
assert(ret != Z_STREAM_ERROR); /* state not clobbered */
DCHECK_NE(ret, Z_STREAM_ERROR); /* state not clobbered */
have = zlib_chunk - stream_data.avail_out;
dst_idx += have;
if (dst_idx + zlib_chunk > dst->size()) {
......@@ -77,11 +79,11 @@ unsigned int ZlibStrategy::ZlibCompress(BufferStr* src, BufferStr* dst) {
}
out = &((*dst)[dst_idx]);
} while (stream_data.avail_out == 0);
assert(stream_data.avail_in == 0); /* all input will be used */
DCHECK_EQ(stream_data.avail_in, 0); /* all input will be used */
/* done when last data in file processed */
} while (flush != Z_FINISH);
assert(ret == Z_STREAM_END); /* stream will be complete */
DCHECK_EQ(ret, Z_STREAM_END); /* stream will be complete */
/* clean up and return */
(void)deflateEnd(&stream_data);
......@@ -125,7 +127,7 @@ unsigned int ZlibStrategy::ZlibUncompress(BufferStr* src, BufferStr* dst) {
stream_data.avail_out = zlib_chunk;
stream_data.next_out = out;
ret = inflate(&stream_data, Z_NO_FLUSH);
assert(ret != Z_STREAM_ERROR); /* state not clobbered */
DCHECK_NE(ret, Z_STREAM_ERROR); /* state not clobbered */
switch (ret) {
case Z_NEED_DICT:
ret = Z_DATA_ERROR; /* and fall through */
......
......@@ -24,6 +24,8 @@
#include <mutex>
#include <thread>
#include <vector>
#include "modules/common/log.h"
#include "modules/common/macro.h"
/// The namespace threadpool contains a thread pool and related utility classes.
......@@ -38,17 +40,11 @@ class LockingPtr {
mutex_.lock();
}
~LockingPtr() {
mutex_.unlock();
}
~LockingPtr() { mutex_.unlock(); }
T& operator*() const {
return *obj_;
}
T& operator*() const { return *obj_; }
T* operator->() const {
return obj_;
}
T* operator->() const { return obj_; }
private:
T* obj_;
......@@ -67,9 +63,7 @@ class ScopeGuard {
}
}
void Disable() {
is_active_ = false;
}
void Disable() { is_active_ = false; }
private:
std::function<void()> const function_;
......@@ -88,25 +82,15 @@ class FifoScheduler {
return true;
}
void Pop() {
task_queue_.pop_front();
}
void Pop() { task_queue_.pop_front(); }
TaskType const& Top() const {
return task_queue_.front();
}
TaskType const& Top() const { return task_queue_.front(); }
size_t Size() const {
return task_queue_.size();
}
size_t Size() const { return task_queue_.size(); }
bool Empty() const {
return task_queue_.empty();
}
bool Empty() const { return task_queue_.empty(); }
void Clear() {
task_queue_.clear();
}
void Clear() { task_queue_.clear(); }
protected:
std::deque<TaskType> task_queue_;
......@@ -117,7 +101,7 @@ class WorkerThread
: public std::enable_shared_from_this<WorkerThread<ThreadPool>> {
public:
explicit WorkerThread(std::shared_ptr<ThreadPool> const& pool) : pool_(pool) {
assert(pool);
DCHECK(pool);
}
void DiedUnexpectedly() {
......@@ -135,9 +119,7 @@ class WorkerThread
pool_->worker_destructed(this->shared_from_this());
}
void join() {
thread_->join();
}
void join() { thread_->join(); }
static void create_and_attach(std::shared_ptr<ThreadPool> const& pool) {
std::shared_ptr<WorkerThread> worker(new WorkerThread(pool));
......@@ -182,9 +164,7 @@ class ThreadPoolImpl : public std::enable_shared_from_this<ThreadPoolImpl> {
/*! Gets the number of threads in the pool.
* \return The number of threads.
*/
size_t Size() const volatile {
return worker_count_;
}
size_t Size() const volatile { return worker_count_; }
// is only called once
void shutdown() {
......@@ -212,9 +192,7 @@ class ThreadPoolImpl : public std::enable_shared_from_this<ThreadPoolImpl> {
/*! Returns the number of tasks which are currently executed.
* \return The number of active tasks.
*/
size_t active() const volatile {
return active_worker_count_;
}
size_t active() const volatile { return active_worker_count_; }
/*! Returns the number of tasks which are ready for execution.
* \return The number of pending tasks.
......@@ -431,13 +409,9 @@ class ThreadPool {
}
}
~ThreadPool() {
Shutdown();
}
~ThreadPool() { Shutdown(); }
size_t Size() const {
return threadpool_impl_->Size();
}
size_t Size() const { return threadpool_impl_->Size(); }
void Shutdown() {
threadpool_impl_->shutdown();
......@@ -448,21 +422,13 @@ class ThreadPool {
return threadpool_impl_->schedule(task);
}
size_t active() const {
return threadpool_impl_->active();
}
size_t active() const { return threadpool_impl_->active(); }
size_t pending() const {
return threadpool_impl_->pending();
}
size_t pending() const { return threadpool_impl_->pending(); }
void Clear() {
return threadpool_impl_->Clear();
}
void Clear() { return threadpool_impl_->Clear(); }
bool Empty() const {
return threadpool_impl_->Empty();
}
bool Empty() const { return threadpool_impl_->Empty(); }
void wait(size_t const task_threshold = 0) const {
threadpool_impl_->wait(task_threshold);
......
......@@ -16,9 +16,6 @@
#include "modules/localization/msf/local_map/base_map/base_map.h"
#include <set>
#include <string>
#include "modules/common/log.h"
#include "modules/localization/msf/common/util/system_utility.h"
......@@ -203,7 +200,8 @@ void BaseMap::LoadMapNodes(std::set<MapNodeIndex>* map_ids) {
}
void BaseMap::PreloadMapNodes(std::set<MapNodeIndex>* map_ids) {
assert(static_cast<int>(map_ids->size()) <= map_node_cache_lvl2_->Capacity());
DCHECK_LE(static_cast<int>(map_ids->size()),
map_node_cache_lvl2_->Capacity());
// check in cacheL2
typename std::set<MapNodeIndex>::iterator itr = map_ids->begin();
while (itr != map_ids->end()) {
......@@ -379,12 +377,12 @@ void BaseMap::PreloadMapArea(const Eigen::Vector3d& location,
for (int i = -1; i < 2; ++i) {
Eigen::Vector3d pt;
pt[0] = location[0] + x_direction * 1.5 *
this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] + static_cast<double>(i) *
this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[0] = location[0] +
x_direction * 1.5 * this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] +
static_cast<double>(i) * this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[2] = 0;
map_id = MapNodeIndex::GetMapNodeIndex(*(this->map_config_), pt,
resolution_id, zone_id);
......@@ -392,12 +390,12 @@ void BaseMap::PreloadMapArea(const Eigen::Vector3d& location,
}
for (int i = -1; i < 2; ++i) {
Eigen::Vector3d pt;
pt[0] = location[0] + static_cast<double>(i) *
this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] + y_direction * 1.5 *
this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[0] = location[0] +
static_cast<double>(i) * this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] +
y_direction * 1.5 * this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[2] = 0;
map_id = MapNodeIndex::GetMapNodeIndex(*(this->map_config_), pt,
resolution_id, zone_id);
......@@ -405,12 +403,12 @@ void BaseMap::PreloadMapArea(const Eigen::Vector3d& location,
}
{
Eigen::Vector3d pt;
pt[0] = location[0] + x_direction * 1.5 *
this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] + y_direction * 1.5 *
this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[0] = location[0] +
x_direction * 1.5 * this->map_config_->map_node_size_x_ *
map_pixel_resolution;
pt[1] = location[1] +
y_direction * 1.5 * this->map_config_->map_node_size_y_ *
map_pixel_resolution;
pt[2] = 0;
map_id = MapNodeIndex::GetMapNodeIndex(*(this->map_config_), pt,
resolution_id, zone_id);
......@@ -431,14 +429,12 @@ bool BaseMap::LoadMapArea(const Eigen::Vector3d& seed_pt3d,
this->map_config_->map_resolutions_[resolution_id];
/// top left
Eigen::Vector3d pt_top_left;
pt_top_left[0] =
seed_pt3d[0] -
(this->map_config_->map_node_size_x_ * map_pixel_resolution / 2.0) -
static_cast<int>(filter_size_x / 2) * map_pixel_resolution;
pt_top_left[1] =
seed_pt3d[1] -
(this->map_config_->map_node_size_y_ * map_pixel_resolution / 2.0) -
static_cast<int>(filter_size_y / 2) * map_pixel_resolution;
pt_top_left[0] = seed_pt3d[0] - (this->map_config_->map_node_size_x_ *
map_pixel_resolution / 2.0) -
static_cast<int>(filter_size_x / 2) * map_pixel_resolution;
pt_top_left[1] = seed_pt3d[1] - (this->map_config_->map_node_size_y_ *
map_pixel_resolution / 2.0) -
static_cast<int>(filter_size_y / 2) * map_pixel_resolution;
pt_top_left[2] = 0;
MapNodeIndex map_id = MapNodeIndex::GetMapNodeIndex(
*(this->map_config_), pt_top_left, resolution_id, zone_id);
......@@ -455,10 +451,9 @@ bool BaseMap::LoadMapArea(const Eigen::Vector3d& seed_pt3d,
/// top right
Eigen::Vector3d pt_top_right;
pt_top_right[0] =
seed_pt3d[0] +
(this->map_config_->map_node_size_x_ * map_pixel_resolution / 2.0) +
static_cast<int>(filter_size_x / 2) * map_pixel_resolution;
pt_top_right[0] = seed_pt3d[0] + (this->map_config_->map_node_size_x_ *
map_pixel_resolution / 2.0) +
static_cast<int>(filter_size_x / 2) * map_pixel_resolution;
pt_top_right[1] = pt_top_left[1];
pt_top_left[2] = 0;
map_id = MapNodeIndex::GetMapNodeIndex(*(this->map_config_), pt_top_right,
......
......@@ -21,6 +21,7 @@
#include <map>
#include <set>
#include <string>
#include "modules/localization/msf/local_map/base_map/base_map_cache.h"
#include "modules/localization/msf/local_map/base_map/base_map_config.h"
#include "modules/localization/msf/local_map/base_map/base_map_fwd.h"
......@@ -92,13 +93,9 @@ class BaseMap {
void LoadBinary(FILE* file, std::string map_folder_path = "");
/**@brief Get the map config. */
inline const BaseMapConfig& GetConfig() const {
return *map_config_;
}
inline const BaseMapConfig& GetConfig() const { return *map_config_; }
/**@brief Get the map config. */
inline BaseMapConfig& GetConfig() {
return *map_config_;
}
inline BaseMapConfig& GetConfig() { return *map_config_; }
protected:
/**@brief Load map node by index.*/
......
......@@ -15,7 +15,6 @@
*****************************************************************************/
#include "modules/localization/msf/local_map/base_map/base_map_matrix.h"
#include <assert.h>
namespace apollo {
namespace localization {
......@@ -27,18 +26,14 @@ BaseMapMatrix::~BaseMapMatrix() {}
BaseMapMatrix::BaseMapMatrix(const BaseMapMatrix& cells) {}
unsigned int BaseMapMatrix::LoadBinary(unsigned char* buf) {
return 0;
}
unsigned int BaseMapMatrix::LoadBinary(unsigned char* buf) { return 0; }
unsigned int BaseMapMatrix::CreateBinary(unsigned char* buf,
unsigned int buf_size) const {
return 0;
}
unsigned int BaseMapMatrix::GetBinarySize() const {
return 0;
}
unsigned int BaseMapMatrix::GetBinarySize() const { return 0; }
} // namespace msf
} // namespace localization
......
......@@ -17,9 +17,10 @@
#ifndef MODULES_LOCALIZATION_MSF_LOCAL_MAP_BASE_MAP_BASE_MAP_MATRIX_H
#define MODULES_LOCALIZATION_MSF_LOCAL_MAP_BASE_MAP_BASE_MAP_MATRIX_H
#include <assert.h>
#include <opencv2/opencv.hpp>
#include <vector>
#include "opencv2/opencv.hpp"
#include "modules/localization/msf/local_map/base_map/base_map_fwd.h"
namespace apollo {
......
......@@ -32,16 +32,15 @@ using apollo::common::util::DirectoryExists;
using apollo::common::util::EnsureDirectory;
BaseMapNode::BaseMapNode(BaseMapMatrix* matrix, CompressionStrategy* strategy)
: map_matrix_(matrix), compression_strategy_(strategy) {
is_changed_ = false;
data_is_ready_ = false;
is_reserved_ = false;
min_altitude_ = 1e6;
}
: map_matrix_(matrix), compression_strategy_(strategy) {}
BaseMapNode::~BaseMapNode() {
delete map_matrix_;
delete compression_strategy_;
if (map_matrix_ != nullptr) {
delete map_matrix_;
}
if (compression_strategy_ != nullptr) {
delete compression_strategy_;
}
}
void BaseMapNode::Init(const BaseMapConfig* map_config,
......@@ -298,7 +297,7 @@ unsigned int BaseMapNode::GetHeaderBinarySize() const {
// }
unsigned int BaseMapNode::LoadBodyBinary(std::vector<unsigned char>* buf) {
if (compression_strategy_ == NULL) {
if (compression_strategy_ == nullptr) {
return map_matrix_->LoadBinary(&((*buf)[0]));
}
std::vector<unsigned char> buf_uncompressed;
......@@ -310,7 +309,7 @@ unsigned int BaseMapNode::LoadBodyBinary(std::vector<unsigned char>* buf) {
unsigned int BaseMapNode::CreateBodyBinary(
std::vector<unsigned char>* buf) const {
if (compression_strategy_ == NULL) {
if (compression_strategy_ == nullptr) {
unsigned int body_size = GetBodyBinarySize();
buf->resize(body_size);
map_matrix_->CreateBinary(&((*buf)[0]), body_size);
......@@ -421,8 +420,8 @@ Eigen::Vector2d BaseMapNode::GetLeftTopCorner(const BaseMapConfig& config,
coord[1] = config.map_range_.GetMinY() +
config.map_node_size_y_ *
config.map_resolutions_[index.resolution_id_] * index.m_;
assert(coord[0] < config.map_range_.GetMaxX());
assert(coord[1] < config.map_range_.GetMaxY());
DCHECK_LT(coord[0], config.map_range_.GetMaxX());
DCHECK_LT(coord[1], config.map_range_.GetMaxY());
return coord;
}
......
......@@ -58,46 +58,26 @@ class BaseMapNode {
// /**@brief Set compression strategy. */
// void SetCompressionStrategy(compression::CompressionStrategy* strategy);
/**@brief Get map cell matrix. */
inline const BaseMapMatrix& GetMapCellMatrix() const {
return *map_matrix_;
}
inline const BaseMapMatrix& GetMapCellMatrix() const { return *map_matrix_; }
inline BaseMapMatrix& GetMapCellMatrix() {
return *map_matrix_;
}
inline BaseMapMatrix& GetMapCellMatrix() { return *map_matrix_; }
/**@brief Get the map settings. */
inline const BaseMapConfig& GetMapConfig() const {
return *map_config_;
}
inline const BaseMapConfig& GetMapConfig() const { return *map_config_; }
/**@brief Set the map node index. */
inline void SetMapNodeIndex(const MapNodeIndex& index) {
index_ = index;
}
inline void SetMapNodeIndex(const MapNodeIndex& index) { index_ = index; }
/**@brief Get the map node index. */
inline const MapNodeIndex& GetMapNodeIndex() const {
return index_;
}
inline const MapNodeIndex& GetMapNodeIndex() const { return index_; }
/**@brief Set if the map node is reserved. */
inline void SetIsReserved(bool is_reserved) {
is_reserved_ = is_reserved;
}
inline void SetIsReserved(bool is_reserved) { is_reserved_ = is_reserved; }
/**@brief Get if the map node is reserved. */
inline bool GetIsReserved() const {
return is_reserved_;
}
inline bool GetIsReserved() const { return is_reserved_; }
/**@brief Get if the map data has changed. */
inline bool GetIsChanged() const {
return is_changed_;
}
inline bool GetIsChanged() const { return is_changed_; }
/**@brief Set if the map node data has changed. */
inline void SetIsChanged(bool is) {
is_changed_ = is;
}
inline void SetIsChanged(bool is) { is_changed_ = is; }
/**@brief Get if the map node data is ready*/
inline bool GetIsReady() const {
return data_is_ready_;
}
inline bool GetIsReady() const { return data_is_ready_; }
/**@brief Get the left top corner of the map node. */
// inline const idl::car::core::numerical::Vector2D& GetLeftTopCorner()
// const {
......@@ -196,18 +176,18 @@ class BaseMapNode {
/**@brief The data structure of the map datas, which is a matrix. */
BaseMapMatrix* map_matrix_;
/**@brief If the node is reserved in map. */
bool is_reserved_;
bool is_reserved_ = false;
/**@brief Has the map node been changed. */
bool is_changed_;
bool is_changed_ = false;
/* *@brief Indicate map node data is ready*/
bool data_is_ready_;
bool data_is_ready_ = false;
/**@brief The body binary size in file. It's useful when reading and writing
* files. */
mutable unsigned int file_body_binary_size_ = 0;
/**@bried The compression strategy. */
CompressionStrategy* compression_strategy_;
CompressionStrategy* compression_strategy_ = nullptr;
/**@brief The min altitude of point cloud in the node. */
float min_altitude_;
float min_altitude_ = 1e6;
};
} // namespace msf
......
......@@ -15,19 +15,17 @@
*****************************************************************************/
#include "modules/localization/msf/local_map/base_map/base_map_node_index.h"
#include <sstream>
#include <string>
#include "modules/common/log.h"
namespace apollo {
namespace localization {
namespace msf {
MapNodeIndex::MapNodeIndex() {
resolution_id_ = 0;
zone_id_ = 50;
m_ = 0;
n_ = 0;
}
MapNodeIndex::MapNodeIndex() {}
bool MapNodeIndex::operator<(const MapNodeIndex& index) const {
if (resolution_id_ < index.resolution_id_) {
......@@ -84,7 +82,7 @@ MapNodeIndex MapNodeIndex::GetMapNodeIndex(const BaseMapConfig& option,
const Eigen::Vector2d& coordinate,
unsigned int resolution_id,
int zone_id) {
assert(resolution_id < option.map_resolutions_.size());
DCHECK_LT(resolution_id, option.map_resolutions_.size());
MapNodeIndex index;
index.resolution_id_ = resolution_id;
index.zone_id_ = zone_id;
......@@ -100,7 +98,7 @@ MapNodeIndex MapNodeIndex::GetMapNodeIndex(const BaseMapConfig& option,
index.m_ = m;
index.n_ = n;
} else {
assert(0 == 1); // should never reach here
DCHECK(false); // should never reach here
}
return index;
}
......
......@@ -19,6 +19,7 @@
#include <iostream>
#include <string>
#include "modules/localization/msf/local_map/base_map/base_map_config.h"
#include "modules/localization/msf/local_map/base_map/base_map_fwd.h"
......@@ -77,14 +78,14 @@ class MapNodeIndex {
/**@brief The ID of the resolution.
* Should be less than BaseMapConfig::map_resolutions_.size(). */
unsigned int resolution_id_;
unsigned int resolution_id_ = 0;
/**@brief The zone ID. 1 - 60 and -1 - -60.
* The positive value is the zone at the north hemisphere. */
int zone_id_;
int zone_id_ = 50;
/**@brief The map node ID at the northing direction. */
unsigned int m_;
unsigned int m_ = 0;
/**@brief The map node ID at the easting direction. */
unsigned int n_;
unsigned int n_ = 0;
};
} // namespace msf
......
......@@ -15,7 +15,8 @@
*****************************************************************************/
#include "modules/localization/msf/local_map/base_map/base_map_pool.h"
#include <set>
#include "modules/common/log.h"
#include "modules/localization/msf/local_map/base_map/base_map_config.h"
#include "modules/localization/msf/local_map/base_map/base_map_node.h"
#include "modules/localization/msf/local_map/base_map/base_map_node_index.h"
......@@ -28,9 +29,7 @@ BaseMapNodePool::BaseMapNodePool(unsigned int pool_size,
unsigned int thread_size)
: pool_size_(pool_size), node_reset_workers_(thread_size) {}
BaseMapNodePool::~BaseMapNodePool() {
Release();
}
BaseMapNodePool::~BaseMapNodePool() { Release(); }
void BaseMapNodePool::Initial(const BaseMapConfig* map_config,
bool is_fixed_size) {
......@@ -95,7 +94,7 @@ void BaseMapNodePool::FreeMapNodeTask(BaseMapNode* map_node) {
{
boost::unique_lock<boost::mutex> lock(mutex_);
typename std::set<BaseMapNode*>::iterator f = busy_nodes_.find(map_node);
assert(f != busy_nodes_.end());
DCHECK(f != busy_nodes_.end());
free_list_.push_back(*f);
busy_nodes_.erase(f);
}
......@@ -106,17 +105,11 @@ void BaseMapNodePool::InitNewMapNode(BaseMapNode* node) {
return;
}
void BaseMapNodePool::FinalizeMapNode(BaseMapNode* node) {
node->Finalize();
}
void BaseMapNodePool::FinalizeMapNode(BaseMapNode* node) { node->Finalize(); }
void BaseMapNodePool::DellocMapNode(BaseMapNode* node) {
delete node;
}
void BaseMapNodePool::DellocMapNode(BaseMapNode* node) { delete node; }
void BaseMapNodePool::ResetMapNode(BaseMapNode* node) {
node->ResetMapNode();
}
void BaseMapNodePool::ResetMapNode(BaseMapNode* node) { node->ResetMapNode(); }
} // namespace msf
} // namespace localization
......
......@@ -17,9 +17,11 @@
#ifndef MODULES_LOCALIZATION_MSF_LOCAL_MAP_BASE_MAP_BASE_MAP_POOL_H
#define MODULES_LOCALIZATION_MSF_LOCAL_MAP_BASE_MAP_BASE_MAP_POOL_H
#include <boost/thread.hpp>
#include <list>
#include <set>
#include "boost/thread.hpp"
#include "modules/localization/msf/common/util/threadpool.h"
#include "modules/localization/msf/local_map/base_map/base_map_fwd.h"
......@@ -53,9 +55,7 @@ class BaseMapNodePool {
* */
void FreeMapNode(BaseMapNode* map_node);
/**@brief Get the size of pool. */
unsigned int GetPoolSize() {
return pool_size_;
}
unsigned int GetPoolSize() { return pool_size_; }
private:
/**@brief The task function of the thread pool for release node.
......
......@@ -15,7 +15,10 @@
*****************************************************************************/
#include "modules/localization/msf/local_map/lossless_map/lossless_map.h"
#include <vector>
#include "modules/common/log.h"
#include "modules/localization/msf/local_map/lossless_map/lossless_map_node.h"
namespace apollo {
......@@ -50,7 +53,7 @@ void LosslessMap::SetValueLayer(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetValue(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<unsigned char>* values) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -60,7 +63,7 @@ void LosslessMap::GetValue(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetValueSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<unsigned char>* values) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -69,7 +72,7 @@ void LosslessMap::GetValueSafe(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetVar(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id, std::vector<float>* vars) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -79,7 +82,7 @@ void LosslessMap::GetVar(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<float>* vars) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -88,7 +91,7 @@ void LosslessMap::GetVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetAlt(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id, std::vector<float>* alts) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -98,7 +101,7 @@ void LosslessMap::GetAlt(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetAltSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<float>* alts) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -108,7 +111,7 @@ void LosslessMap::GetAltSafe(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetAltVar(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<float>* alt_vars) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -118,7 +121,7 @@ void LosslessMap::GetAltVar(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetAltVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<float>* alt_vars) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -128,7 +131,7 @@ void LosslessMap::GetAltVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetCount(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<unsigned int>* counts) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -138,7 +141,7 @@ void LosslessMap::GetCount(const Eigen::Vector3d& coordinate, int zone_id,
void LosslessMap::GetCountSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id,
std::vector<unsigned int>* counts) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -147,7 +150,7 @@ void LosslessMap::GetCountSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned char LosslessMap::GetValue(const Eigen::Vector3d& coordinate,
int zone_id, unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -157,7 +160,7 @@ unsigned char LosslessMap::GetValue(const Eigen::Vector3d& coordinate,
unsigned char LosslessMap::GetValueSafe(const Eigen::Vector3d& coordinate,
int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -166,7 +169,7 @@ unsigned char LosslessMap::GetValueSafe(const Eigen::Vector3d& coordinate,
float LosslessMap::GetVar(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -175,7 +178,7 @@ float LosslessMap::GetVar(const Eigen::Vector3d& coordinate, int zone_id,
float LosslessMap::GetVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -184,7 +187,7 @@ float LosslessMap::GetVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
float LosslessMap::GetAlt(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -193,7 +196,7 @@ float LosslessMap::GetAlt(const Eigen::Vector3d& coordinate, int zone_id,
float LosslessMap::GetAltSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -202,7 +205,7 @@ float LosslessMap::GetAltSafe(const Eigen::Vector3d& coordinate, int zone_id,
float LosslessMap::GetAltVar(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -211,7 +214,7 @@ float LosslessMap::GetAltVar(const Eigen::Vector3d& coordinate, int zone_id,
float LosslessMap::GetAltVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......@@ -220,7 +223,7 @@ float LosslessMap::GetAltVarSafe(const Eigen::Vector3d& coordinate, int zone_id,
unsigned int LosslessMap::GetCount(const Eigen::Vector3d& coordinate,
int zone_id, unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
......@@ -230,7 +233,7 @@ unsigned int LosslessMap::GetCount(const Eigen::Vector3d& coordinate,
unsigned int LosslessMap::GetCountSafe(const Eigen::Vector3d& coordinate,
int zone_id,
unsigned int resolution_id) {
assert(resolution_id < map_config_->map_resolutions_.size());
DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
MapNodeIndex index = MapNodeIndex::GetMapNodeIndex(*map_config_, coordinate,
resolution_id, zone_id);
LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
......
......@@ -103,9 +103,7 @@ unsigned int LosslessMapSingleCell::GetBinarySize() const {
}
// ======================LosslessMapCell===========================
LosslessMapCell::LosslessMapCell() {
layer_num = 1;
}
LosslessMapCell::LosslessMapCell() { layer_num = 1; }
void LosslessMapCell::Reset() {
for (unsigned int i = 0; i < IDL_CAR_NUM_RESERVED_MAP_LAYER; ++i) {
......@@ -116,10 +114,10 @@ void LosslessMapCell::Reset() {
void LosslessMapCell::SetValueLayer(double altitude, unsigned char intensity,
double altitude_thres) {
assert(layer_num <= IDL_CAR_NUM_RESERVED_MAP_LAYER);
DCHECK_LE(layer_num, IDL_CAR_NUM_RESERVED_MAP_LAYER);
unsigned int best_layer_id = GetLayerId(altitude);
assert(best_layer_id < layer_num);
DCHECK_LT(best_layer_id, layer_num);
if (best_layer_id == 0) {
if (layer_num < IDL_CAR_NUM_RESERVED_MAP_LAYER) {
// No layer yet, create a new one
......@@ -157,7 +155,7 @@ void LosslessMapCell::SetValueLayer(double altitude, unsigned char intensity,
}
void LosslessMapCell::SetValue(double altitude, unsigned char intensity) {
assert(layer_num <= IDL_CAR_NUM_RESERVED_MAP_LAYER);
DCHECK_LE(layer_num, IDL_CAR_NUM_RESERVED_MAP_LAYER);
LosslessMapSingleCell& cell = map_cells[0];
cell.AddSample(static_cast<float>(altitude), static_cast<float>(intensity));
}
......@@ -188,7 +186,7 @@ unsigned int LosslessMapCell::CreateBinary(unsigned char* buf,
for (size_t i = 0; i < layer_num; ++i) {
const LosslessMapSingleCell& cell = map_cells[i];
unsigned int processed_size = cell.CreateBinary(pp, buf_size);
assert(buf_size >= processed_size);
DCHECK_GE(buf_size, processed_size);
buf_size -= processed_size;
pp += processed_size;
}
......@@ -351,7 +349,7 @@ unsigned int LosslessMapMatrix::CreateBinary(unsigned char* buf,
for (unsigned int x = 0; x < cols_; ++x) {
const LosslessMapCell& cell = GetMapCell(y, x);
unsigned int processed_size = cell.CreateBinary(pp, buf_size);
assert(buf_size >= processed_size);
DCHECK_GE(buf_size, processed_size);
buf_size -= processed_size;
pp += processed_size;
}
......
......@@ -19,6 +19,7 @@
#include <vector>
#include "modules/common/log.h"
#include "modules/localization/msf/local_map/base_map/base_map_matrix.h"
#include "modules/localization/msf/local_map/base_map/base_map_node.h"
......@@ -112,31 +113,23 @@ struct LosslessMapCell {
return static_cast<unsigned char>(map_cells[0].intensity);
}
/**@brief Get the variance of the intensity of the map cell. */
inline float GetVar() const {
return map_cells[0].intensity_var;
}
inline float GetVar() const { return map_cells[0].intensity_var; }
/**@brief Get the average altitude of the map cell. */
inline float GetAlt() const {
return map_cells[0].altitude;
}
inline float GetAlt() const { return map_cells[0].altitude; }
/**@brief Get the variance of the altitude of the map cell. */
inline float GetAltVar() const {
return map_cells[0].altitude_var;
}
inline float GetAltVar() const { return map_cells[0].altitude_var; }
/**@brief Get the count of the samples in the map cell. */
inline unsigned int GetCount() const {
return map_cells[0].count;
}
inline unsigned int GetCount() const { return map_cells[0].count; }
/**@brief Get a perticular layer in the map cell. The layer 0 is the layer
* includes all the samples. */
LosslessMapSingleCell& GetLayer(unsigned int layer_id) {
assert(layer_id < layer_num);
DCHECK_LT(layer_id, layer_num);
return map_cells[layer_id];
}
/**@brief Get a perticular layer in the map cell. The layer 0 is the layer
* includes all the samples. */
const LosslessMapSingleCell& GetLayer(unsigned int layer_id) const {
assert(layer_id < layer_num);
DCHECK_LT(layer_id, layer_num);
return map_cells[layer_id];
}
......@@ -179,14 +172,14 @@ class LosslessMapMatrix : public BaseMapMatrix {
/**@brief Get a map cell. */
inline const LosslessMapCell& GetMapCell(unsigned int row,
unsigned int col) const {
assert(row < rows_);
assert(col < cols_);
DCHECK_LT(row, rows_);
DCHECK_LT(col, cols_);
return map_cells_[row * cols_ + col];
}
/**@brief Get a map cell. */
inline LosslessMapCell& GetMapCell(unsigned int row, unsigned int col) {
assert(row < rows_);
assert(col < cols_);
DCHECK_LT(row, rows_);
DCHECK_LT(col, cols_);
return map_cells_[row * cols_ + col];
}
......
......@@ -17,6 +17,8 @@
#include "modules/localization/msf/local_map/lossless_map/lossless_map_node.h"
#include <vector>
#include "modules/common/log.h"
#include "modules/localization/msf/local_map/lossless_map/lossless_map_config.h"
namespace apollo {
......@@ -33,7 +35,7 @@ void LosslessMapNode::SetValue(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.SetValue(coordinate[2], intensity);
......@@ -69,7 +71,7 @@ void LosslessMapNode::SetValueLayer(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.SetValueLayer(
......@@ -84,7 +86,7 @@ void LosslessMapNode::GetValue(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.GetValue(values);
......@@ -96,7 +98,7 @@ void LosslessMapNode::GetVar(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.GetVar(vars);
......@@ -108,7 +110,7 @@ void LosslessMapNode::GetAlt(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.GetAlt(alts);
......@@ -120,7 +122,7 @@ void LosslessMapNode::GetAltVar(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.GetAltVar(alt_vars);
......@@ -132,7 +134,7 @@ void LosslessMapNode::GetCount(const Eigen::Vector3d& coordinate,
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
map_cell.GetCount(counts);
......@@ -144,7 +146,7 @@ unsigned char LosslessMapNode::GetValue(
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
return map_cell.GetValue();
......@@ -155,7 +157,7 @@ float LosslessMapNode::GetVar(const Eigen::Vector3d& coordinate) const {
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
return map_cell.GetVar();
......@@ -166,7 +168,7 @@ float LosslessMapNode::GetAlt(const Eigen::Vector3d& coordinate) const {
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
return map_cell.GetAlt();
......@@ -177,7 +179,7 @@ float LosslessMapNode::GetAltVar(const Eigen::Vector3d& coordinate) const {
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
return map_cell.GetAltVar();
......@@ -189,7 +191,7 @@ unsigned int LosslessMapNode::GetCount(
unsigned int x = 0;
unsigned int y = 0;
bool is_success = GetCoordinate(coord2d, &x, &y);
assert(is_success);
DCHECK(is_success);
LosslessMapCell& map_cell =
static_cast<LosslessMapMatrix*>(map_matrix_)->GetMapCell(y, x);
return map_cell.GetCount();
......
......@@ -16,10 +16,11 @@
#include "modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.h"
#include <stdio.h>
#include <boost/filesystem.hpp>
#include <cstdio>
#include <fstream>
#include "boost/filesystem.hpp"
#include "modules/common/log.h"
#include "modules/common/util/file.h"
......@@ -35,10 +36,9 @@ using apollo::common::util::EnsureDirectory;
unsigned char color_table[3][3] = {{0, 0, 255}, {0, 255, 0}, {255, 0, 0}};
const char car_img_path[3][1024] = {
"modules/localization/msf/local_tool/local_visualization/img/red_car.png",
"modules/localization/msf/local_tool/local_visualization/img/green_car.png",
"modules/localization/msf/local_tool/local_visualization/img/blue_car.png"
};
"modules/localization/msf/local_tool/local_visualization/img/red_car.png",
"modules/localization/msf/local_tool/local_visualization/img/green_car.png",
"modules/localization/msf/local_tool/local_visualization/img/blue_car.png"};
// =================VisualizationEngine=================
bool MapImageKey::operator<(const MapImageKey &key) const {
......@@ -90,8 +90,7 @@ VisualizationEngine::VisualizationEngine()
: map_image_cache_(20),
image_window_(1024, 1024, CV_8UC3, cv::Scalar(0, 0, 0)),
big_window_(3072, 3072, CV_8UC3),
tips_window_(48, 1024, CV_8UC3, cv::Scalar(0, 0, 0)) {
}
tips_window_(48, 1024, CV_8UC3, cv::Scalar(0, 0, 0)) {}
bool VisualizationEngine::Init(const std::string &map_folder,
const std::string &map_visual_folder,
......@@ -257,8 +256,8 @@ void VisualizationEngine::Draw() {
for (int i = 0; i < 3; ++i) {
for (int j = 0; j < 3; ++j) {
subMat_[i][j].copyTo(
big_window_(cv::Rect(j * 1024, i * 1024, 1024, 1024)));
subMat_[i]
[j].copyTo(big_window_(cv::Rect(j * 1024, i * 1024, 1024, 1024)));
}
}
......@@ -492,10 +491,9 @@ void VisualizationEngine::DrawLegend() {
unsigned char b = color_table[i % 3][0];
unsigned char g = color_table[i % 3][1];
unsigned char r = color_table[i % 3][2];
cv::circle(
image_window_,
cv::Point(755, (15 + textSize.height) * (i + 1) - textSize.height / 2),
8, cv::Scalar(b, g, r), 3);
cv::circle(image_window_, cv::Point(755, (15 + textSize.height) * (i + 1) -
textSize.height / 2),
8, cv::Scalar(b, g, r), 3);
}
}
......@@ -743,9 +741,9 @@ void VisualizationEngine::CloudToMat(const Eigen::Affine3d &cur_pose,
Eigen::Vector3d pt_global = cur_pose * velodyne_extrinsic * pt;
int col = static_cast<int>((pt_global[0] - cloud_img_lt_coord_[0]) /
map_param_.map_resolutions[resolution_id_]);
map_param_.map_resolutions[resolution_id_]);
int row = static_cast<int>((pt_global[1] - cloud_img_lt_coord_[1]) /
map_param_.map_resolutions[resolution_id_]);
map_param_.map_resolutions[resolution_id_]);
if (col < 0 || row < 0 ||
col >= static_cast<int>(map_param_.map_node_size_x) ||
row >= static_cast<int>(map_param_.map_node_size_y)) {
......@@ -764,7 +762,7 @@ void VisualizationEngine::CoordToImageKey(const Eigen::Vector2d &coord,
MapImageKey *key) {
key->level = cur_level_;
assert(resolution_id_ < map_param_.map_resolutions.size());
DCHECK_LT(resolution_id_, map_param_.map_resolutions.size());
key->zone_id = zone_id_;
int n = static_cast<int>((coord[0] - map_param_.map_min_x) /
(map_param_.map_node_size_x *
......@@ -784,7 +782,7 @@ void VisualizationEngine::CoordToImageKey(const Eigen::Vector2d &coord,
key->node_north_id = m;
key->node_east_id = n;
} else {
assert(0 == 1); // should never reach here
DCHECK(false); // should never reach here
}
m = static_cast<int>(key->node_north_id) - lt_node_index_.y;
......@@ -870,9 +868,7 @@ void VisualizationEngine::UpdateViewCenter(const double move_x,
_view_center[1] += move_y;
}
void VisualizationEngine::SetScale(const double scale) {
cur_scale_ = scale;
}
void VisualizationEngine::SetScale(const double scale) { cur_scale_ = scale; }
void VisualizationEngine::UpdateScale(const double factor) {
cur_scale_ *= factor;
......
......@@ -15,7 +15,7 @@
*****************************************************************************/
/**
* @file visualization_engine.h
* @file
* @brief The engine for localization visualization.
*/
#ifndef MODULES_LOCALIZATION_MSF_LOCAL_TOOL_VISUALIZATION_ENGINE_H_
......
......@@ -15,9 +15,12 @@
*****************************************************************************/
#include "modules/localization/msf/local_tool/local_visualization/offline_visual/offline_local_visualizer.h"
#include <map>
#include <vector>
#include "boost/filesystem.hpp"
#include "modules/common/log.h"
#include "modules/localization/msf/common/io/velodyne_utility.h"
......@@ -25,26 +28,15 @@ namespace apollo {
namespace localization {
namespace msf {
OfflineLocalVisualizer::OfflineLocalVisualizer()
: map_config_(), resolution_id_(0), zone_id_(0), visual_engine_() {
map_folder_ = "";
map_visual_folder_ = "";
pcd_folder_ = "";
gnss_loc_file_ = "";
lidar_loc_file_ = "";
fusion_loc_file_ = "";
extrinsic_file_ = "";
}
: map_config_(), resolution_id_(0), zone_id_(0), visual_engine_() {}
OfflineLocalVisualizer::~OfflineLocalVisualizer() {}
bool OfflineLocalVisualizer::Init(const std::string &map_folder,
const std::string &map_visual_folder,
const std::string &pcd_folder,
const std::string &pcd_timestamp_file,
const std::string &gnss_loc_file,
const std::string &lidar_loc_file,
const std::string &fusion_loc_file,
const std::string &extrinsic_file) {
bool OfflineLocalVisualizer::Init(
const std::string &map_folder, const std::string &map_visual_folder,
const std::string &pcd_folder, const std::string &pcd_timestamp_file,
const std::string &gnss_loc_file, const std::string &lidar_loc_file,
const std::string &fusion_loc_file, const std::string &extrinsic_file) {
map_folder_ = map_folder;
map_visual_folder_ = map_visual_folder;
pcd_folder_ = pcd_folder;
......@@ -335,12 +327,12 @@ void OfflineLocalVisualizer::PoseAndStdInterpolationByTime(
if (index >= 1) {
double cur_timestamp = in_timestamps[index];
double pre_timestamp = in_timestamps[index - 1];
assert(cur_timestamp != pre_timestamp);
DCHECK_NE(cur_timestamp, pre_timestamp);
double t =
(cur_timestamp - ref_timestamp) / (cur_timestamp - pre_timestamp);
assert(t >= 0.0);
assert(t <= 1.0);
DCHECK_GE(t, 0.0);
DCHECK_LE(t, 1.0);
Eigen::Affine3d pre_pose = in_poses[index - 1];
Eigen::Affine3d cur_pose = in_poses[index];
......
......@@ -24,8 +24,9 @@
#include <map>
#include <string>
#include <vector>
#include "modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.h"
#include "modules/localization/msf/local_map/base_map/base_map_config.h"
#include "modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.h"
namespace apollo {
namespace localization {
......
......@@ -14,9 +14,11 @@
* limitations under the License.
*****************************************************************************/
#include <boost/filesystem.hpp>
#include <boost/program_options.hpp>
#include <vector>
#include "boost/filesystem.hpp"
#include "boost/program_options.hpp"
#include "modules/localization/msf/common/io/velodyne_utility.h"
#include "modules/localization/msf/common/util/extract_ground_plane.h"
#include "modules/localization/msf/common/util/system_utility.h"
......@@ -47,11 +49,10 @@ bool ParseCommandLine(int argc, char* argv[],
// ("use_plane_fitting_ransac",
// boost::program_options::value<bool>()->required(),
// "use plane fitting ransac")
("pcd_folders",
boost::program_options::value<std::vector<std::string>>()
->multitoken()
->composing()
->required(),
("pcd_folders", boost::program_options::value<std::vector<std::string>>()
->multitoken()
->composing()
->required(),
"pcd folders(repeated)")(
"pose_files",
boost::program_options::value<std::vector<std::string>>()
......@@ -327,7 +328,7 @@ int main(int argc, char** argv) {
std::cerr << "[FATAL ERROR] Map node should at least have one layer."
<< std::endl;
}
assert(layer_counts.size() > 0);
DCHECK_GT(layer_counts.size(), 0);
if (layer_counts[layer_id] > 0) {
std::vector<float> layer_alts;
map.GetAltSafe(pt3d, zone_id, resolution_id, &layer_alts);
......@@ -336,7 +337,7 @@ int main(int argc, char** argv) {
<< "[FATAL ERROR] Map node should at least have one layer."
<< std::endl;
}
assert(layer_alts.size() > 0);
DCHECK_GT(layer_alts.size(), 0);
float alt = layer_alts[layer_id];
double height_diff = pt3d[2] - alt;
VarianceOnline(&mean_height_diff, &var_height_diff,
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册