提交 ed5ad5c0 编写于 作者: Q Qi Luo 提交者: Dong Li

Localization : Simple code cleaning to mute compile warnings

上级 38c35cff
......@@ -169,10 +169,10 @@ class ThreadPoolImpl : public std::enable_shared_from_this<ThreadPoolImpl> {
public:
/// Constructor.
ThreadPoolImpl()
: worker_count_(0),
: terminate_all_workers_(false),
worker_count_(0),
target_worker_count_(0),
active_worker_count_(0),
terminate_all_workers_(false) {
active_worker_count_(0) {
m_scheduler.Clear();
}
......
......@@ -71,7 +71,7 @@ LossyMapMatrix2D::LossyMapMatrix2D(const LossyMapMatrix2D& matrix)
}
}
LossyMapMatrix2D& LossyMapMatrix2D::operator= (const LossyMapMatrix2D& matrix) {
LossyMapMatrix2D& LossyMapMatrix2D::operator=(const LossyMapMatrix2D& matrix) {
Init(matrix.rows_, matrix.cols_);
for (unsigned int y = 0; y < rows_; ++y) {
for (unsigned int x = 0; x < cols_; ++x) {
......@@ -143,8 +143,7 @@ uint16_t LossyMapMatrix2D::EncodeVar(const LossyMapCell2D& cell) const {
return intensity_var;
}
void LossyMapMatrix2D::DecodeVar(uint16_t data,
LossyMapCell2D* cell) const {
void LossyMapMatrix2D::DecodeVar(uint16_t data, LossyMapCell2D* cell) const {
float var = data;
var = (var_range_ / var - 1.0) / var_ratio_;
cell->intensity_var = var * var;
......@@ -171,8 +170,7 @@ void LossyMapMatrix2D::DecodeAltitudeGround(uint16_t data,
return;
}
uint16_t LossyMapMatrix2D::EncodeAltitudeAvg(
const LossyMapCell2D& cell) const {
uint16_t LossyMapMatrix2D::EncodeAltitudeAvg(const LossyMapCell2D& cell) const {
float delta_alt = cell.altitude - alt_avg_min_;
delta_alt /= alt_avg_interval_;
int ratio = delta_alt + 0.5;
......@@ -428,18 +426,17 @@ unsigned int LossyMapMatrix2D::GetBinarySize() const {
unsigned int target_size =
sizeof(unsigned int) * 2 + sizeof(float) * 4; // rows and cols and alts
// count, intensity, intensity_var, altitude_avg, altitude_ground
target_size +=
rows_ * cols_ *
(sizeof(unsigned char) + sizeof(unsigned char) + sizeof(uint16_t) +
sizeof(uint16_t) + sizeof(uint16_t));
target_size += rows_ * cols_ *
(sizeof(unsigned char) + sizeof(unsigned char) +
sizeof(uint16_t) + sizeof(uint16_t) + sizeof(uint16_t));
return target_size;
}
void LossyMapMatrix2D::GetIntensityImg(cv::Mat* intensity_img) const {
*intensity_img = cv::Mat(cv::Size(cols_, rows_), CV_8UC1);
for (int y = 0; y < rows_; ++y) {
for (int x = 0; x < cols_; ++x) {
for (unsigned int y = 0; y < rows_; ++y) {
for (unsigned int x = 0; x < cols_; ++x) {
unsigned int id = y * cols_ + x;
intensity_img->at<unsigned char>(y, x) =
(unsigned char)(map_cells_[id].intensity);
......
......@@ -52,8 +52,8 @@ MapNodeIndex GetMapIndexFromMapFolder(const std::string& map_folder) {
}
bool GetAllMapIndex(const std::string& src_map_folder,
const std::string& dst_map_folder,
std::list<MapNodeIndex>* buf) {
const std::string& dst_map_folder,
std::list<MapNodeIndex>* buf) {
std::string src_map_path = src_map_folder + "/map";
std::string dst_map_path = dst_map_folder + "/map";
boost::filesystem::path src_map_path_boost(src_map_path);
......@@ -66,7 +66,6 @@ bool GetAllMapIndex(const std::string& src_map_folder,
// push path of map's index to list
buf->clear();
// std::deque<std::string> map_bin_path;
int index = 0;
boost::filesystem::recursive_directory_iterator end_iter;
boost::filesystem::recursive_directory_iterator iter(src_map_path_boost);
for (; iter != end_iter; ++iter) {
......@@ -95,17 +94,17 @@ bool GetAllMapIndex(const std::string& src_map_folder,
} // namespace localization
} // namespace apollo
using apollo::localization::msf::MapNodeIndex;
using apollo::localization::msf::LossyMapMatrix;
using apollo::localization::msf::LossyMapConfig;
using apollo::localization::msf::LossyMapNodePool;
using apollo::localization::msf::LossyMap;
using apollo::localization::msf::LossyMapNode;
using apollo::localization::msf::LosslessMapNodePool;
using apollo::localization::msf::LosslessMapConfig;
using apollo::localization::msf::LosslessMap;
using apollo::localization::msf::LosslessMapNode;
using apollo::localization::msf::LosslessMapConfig;
using apollo::localization::msf::LosslessMapMatrix;
using apollo::localization::msf::LosslessMapNode;
using apollo::localization::msf::LosslessMapNodePool;
using apollo::localization::msf::LossyMap;
using apollo::localization::msf::LossyMapConfig;
using apollo::localization::msf::LossyMapMatrix;
using apollo::localization::msf::LossyMapNode;
using apollo::localization::msf::LossyMapNodePool;
using apollo::localization::msf::MapNodeIndex;
int main(int argc, char** argv) {
boost::program_options::options_description boost_desc("Allowed options");
......
......@@ -29,10 +29,10 @@ namespace apollo {
namespace localization {
using ::Eigen::Vector3d;
using apollo::common::Status;
using apollo::common::adapter::AdapterManager;
using apollo::common::adapter::ImuAdapter;
using apollo::common::monitor::MonitorMessageItem;
using apollo::common::Status;
using apollo::common::time::Clock;
MSFLocalization::MSFLocalization()
......@@ -124,15 +124,13 @@ Status MSFLocalization::Init() {
switch (state.error_code()) {
case LocalizationErrorCode::INTEG_ERROR:
return Status(common::LOCALIZATION_ERROR_INTEG, state.error_msg());
break;
case LocalizationErrorCode::LIDAR_ERROR:
return Status(common::LOCALIZATION_ERROR_LIDAR, state.error_msg());
break;
case LocalizationErrorCode::GNSS_ERROR:
return Status(common::LOCALIZATION_ERROR_GNSS, state.error_msg());
default:
return Status::OK();
}
return Status::OK();
}
void MSFLocalization::InitParams() {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册