本次阅读的源码为 release-1.0 版本的代码

https://github.com/googlecartographer/cartographer_ros/tree/release-1.0

https://github.com/googlecartographer/cartographer/tree/release-1.0

也可以下载我上传的 全套工作空间的代码,包括 protobuf, cartographer, cartographer_ros, ceres,

https://download.csdn.net/download/tiancailx/11224156,现在上传资源自己不能选下载需要的积分。。。完全靠系统。

本篇文章写了如何从激光雷达数据写成二维栅格地图的过程。

1 local_trajectory_builder_2d类

// cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc
std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
LocalTrajectoryBuilder2D::AddAccumulatedRangeData()
{std::unique_ptr<InsertionResult> insertion_result =InsertIntoSubmap(time, range_data_in_local, gravity_aligned_range_data,pose_estimate, gravity_alignment.rotation());
}std::unique_ptr<LocalTrajectoryBuilder2D::InsertionResult>
LocalTrajectoryBuilder2D::InsertIntoSubmap(const common::Time time, const sensor::RangeData& range_data_in_local,const sensor::RangeData& gravity_aligned_range_data,const transform::Rigid3d& pose_estimate,const Eigen::Quaterniond& gravity_alignment) {// Querying the active submaps must be done here before calling// InsertRangeData() since the queried values are valid for next insertion.std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;for (const std::shared_ptr<Submap2D>& submap : active_submaps_.submaps()) {insertion_submaps.push_back(submap);}active_submaps_.InsertRangeData(range_data_in_local);
}

2 ActiveSubmaps2D类 与 Submap2D类

void ActiveSubmaps2D::InsertRangeData(const sensor::RangeData& range_data) {for (auto& submap : submaps_) {// 将雷达数据写入submapsubmap->InsertRangeData(range_data, range_data_inserter_.get());}if (submaps_.back()->num_range_data() == options_.num_range_data()) {// 当range data 数量达到配置的值时,将新建个submapAddSubmap(range_data.origin.head<2>());}
}void ActiveSubmaps2D::AddSubmap(const Eigen::Vector2f& origin) {if (submaps_.size() > 1) {// This will crop the finished Submap before inserting a new Submap to// reduce peak memory usage a bit.// 新建时,如果submap的个数为2,则需要先将第一个submap设置成finish,并从active submap中删掉FinishSubmap();}// 新建一个active submapsubmaps_.push_back(common::make_unique<Submap2D>(origin, std::unique_ptr<Grid2D>(static_cast<Grid2D*>(CreateGrid(origin).release()))));LOG(INFO) << "Added submap " << matching_submap_index_ + submaps_.size();
}std::unique_ptr<GridInterface> ActiveSubmaps2D::CreateGrid(const Eigen::Vector2f& origin) {constexpr int kInitialSubmapSize = 100;float resolution = options_.grid_options_2d().resolution();// 新建一个ProbalityGridreturn common::make_unique<ProbabilityGrid>(MapLimits(resolution,origin.cast<double>() + 0.5 * kInitialSubmapSize * resolution *Eigen::Vector2d::Ones(),CellLimits(kInitialSubmapSize, kInitialSubmapSize)));
}void Submap2D::InsertRangeData(const sensor::RangeData& range_data,const RangeDataInserterInterface* range_data_inserter) {CHECK(grid_);CHECK(!finished());range_data_inserter->Insert(range_data, grid_.get());set_num_range_data(num_range_data() + 1);
}
void ActiveSubmaps2D::FinishSubmap() {Submap2D* submap = submaps_.front().get();submap->Finish();++matching_submap_index_;submaps_.erase(submaps_.begin());
}void Submap2D::Finish() {CHECK(grid_);CHECK(!finished());// 计算裁剪栅格地图grid_ = grid_->ComputeCroppedGrid();set_finished(true);
}//cartographer/cartographer/mapping/submaps.hvoid set_finished(bool finished) { finished_ = finished; }// cartographer/cartographer/mapping/2d/probability_grid.cc
std::unique_ptr<Grid2D> ProbabilityGrid::ComputeCroppedGrid() const {Eigen::Array2i offset;CellLimits cell_limits;ComputeCroppedLimits(&offset, &cell_limits);const double resolution = limits().resolution();const Eigen::Vector2d max =limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x());std::unique_ptr<ProbabilityGrid> cropped_grid =common::make_unique<ProbabilityGrid>(MapLimits(resolution, max, cell_limits));for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {if (!IsKnown(xy_index + offset)) continue;cropped_grid->SetProbability(xy_index, GetProbability(xy_index + offset));}return std::unique_ptr<Grid2D>(cropped_grid.release());
}

3 ProbabilityGridRangeDataInserter2D类

只在cartographer/cartographer/mapping/internal/2d/local_trajectory_builder_2d.h 中的 ActiveSubmaps2D 进行初始化时构造一次,初始化时计算 hit_table_ 与 miss_table_ ;

// cartographer/cartographer/mapping/2d/probability_grid_range_data_inserter_2d.ccProbabilityGridRangeDataInserter2D::ProbabilityGridRangeDataInserter2D(const proto::ProbabilityGridRangeDataInserterOptions2D& options): options_(options),hit_table_(ComputeLookupTableToApplyCorrespondenceCostOdds(Odds(options.hit_probability()))),miss_table_(ComputeLookupTableToApplyCorrespondenceCostOdds(Odds(options.miss_probability()))) {}void ProbabilityGridRangeDataInserter2D::Insert(const sensor::RangeData& range_data, GridInterface* const grid) const {ProbabilityGrid* const probability_grid = static_cast<ProbabilityGrid*>(grid);// By not finishing the update after hits are inserted, we give hits priority// (i.e. no hits will be ignored because of a miss in the same cell).CastRays(range_data, hit_table_, miss_table_, options_.insert_free_space(),CHECK_NOTNULL(probability_grid));probability_grid->FinishUpdate();
}// cartographer/cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h
class ProbabilityGridRangeDataInserter2D : public RangeDataInserterInterface {// Inserts 'range_data' into 'probability_grid'.virtual void Insert(const sensor::RangeData& range_data,GridInterface* grid) const override;private:const proto::ProbabilityGridRangeDataInserterOptions2D options_;const std::vector<uint16> hit_table_;const std::vector<uint16> miss_table_;
};

3.1 hit_table_ 与 miss_table_ 的初始化

调用了两个在文件probability_values.h中定义的函数。 其中函数CorrespondenceCostToValue是将float类型的数据转换为uint16类型,并将输入从区间 [kMinCorrespondenceCost,kMaxCorrespondenceCost] 映射到 [1,32767]。

函数ProbabilityToCorrespondenceCost实际上是对输入概率值取反,这意味着如果我们的输入描述的是栅格单元的占用概率,那么实际存储的则是栅格单元空闲的概率。

std::vector<uint16> ComputeLookupTableToApplyCorrespondenceCostOdds(float odds/*0.55*/) {std::vector<uint16> result;result.push_back(// 22327 + 32768(kUpdateMarker) = 55095CorrespondenceCostToValue( // 0.6451 --> 22327ProbabilityToCorrespondenceCost( // 0.6451 = 1 - 0.3548ProbabilityFromOdds(odds) )) + // 0.3548 = 0.55/(0.55+1)kUpdateMarker); // constexpr uint16 kUpdateMarker = 1u << 15; // 32768for (int cell = 1; cell != 32768; ++cell) {result.push_back(CorrespondenceCostToValue(ProbabilityToCorrespondenceCost(ProbabilityFromOdds(odds * Odds( // a/(1-a)CorrespondenceCostToProbability( // 1- b(*kValueToCorrespondenceCost)[cell] ) )))) +kUpdateMarker); }return result;
}

3.2 CastRays()

cartographer/cartographer/mapping/internal/2d/ray_casting.cc

void CastRays(const sensor::RangeData& range_data,const std::vector<uint16>& hit_table,const std::vector<uint16>& miss_table,const bool insert_free_space,ProbabilityGrid* const probability_grid) {GrowAsNeeded(range_data, probability_grid);const MapLimits& limits = probability_grid->limits();const double superscaled_resolution = limits.resolution() / kSubpixelScale;const MapLimits superscaled_limits(superscaled_resolution, limits.max(),CellLimits(limits.cell_limits().num_x_cells * kSubpixelScale,limits.cell_limits().num_y_cells * kSubpixelScale));const Eigen::Array2i begin =superscaled_limits.GetCellIndex(range_data.origin.head<2>());// Compute and add the end points.std::vector<Eigen::Array2i> ends;ends.reserve(range_data.returns.size());for (const Eigen::Vector3f& hit : range_data.returns) {ends.push_back(superscaled_limits.GetCellIndex(hit.head<2>()));probability_grid->ApplyLookupTable(ends.back() / kSubpixelScale, hit_table);}if (!insert_free_space) {return;}// Now add the misses.for (const Eigen::Array2i& end : ends) {CastRay(begin, end, miss_table, probability_grid);}// Finally, compute and add empty rays based on misses in the range data.for (const Eigen::Vector3f& missing_echo : range_data.misses) {CastRay(begin, superscaled_limits.GetCellIndex(missing_echo.head<2>()),miss_table, probability_grid);}
}

3.3 ProbabilityGrid::ApplyLookupTable()

//cartographer/cartographer/mapping/2d/probability_grid.cc// Applies the 'odds' specified when calling ComputeLookupTableToApplyOdds()
// to the probability of the cell at 'cell_index' if the cell has not already
// been updated. Multiple updates of the same cell will be ignored until
// FinishUpdate() is called. Returns true if the cell was updated.
//
// If this is the first call to ApplyOdds() for the specified cell, its value
// will be set to probability corresponding to 'odds'.
bool ProbabilityGrid::ApplyLookupTable(const Eigen::Array2i& cell_index,const std::vector<uint16>& table) {DCHECK_EQ(table.size(), kUpdateMarker);const int flat_index = ToFlatIndex(cell_index);uint16* cell = &(*mutable_correspondence_cost_cells())[flat_index];if (*cell >= kUpdateMarker) {return false;}mutable_update_indices()->push_back(flat_index);*cell = table[*cell];DCHECK_GE(*cell, kUpdateMarker);mutable_known_cells_box()->extend(cell_index.matrix());return true;
}

3.4 CastRay()

// Factor for subpixel accuracy of start and end point.
constexpr int kSubpixelScale = 1000;// We divide each pixel in kSubpixelScale x kSubpixelScale subpixels. 'begin'
// and 'end' are coordinates at subpixel precision. We compute all pixels in
// which some part of the line segment connecting 'begin' and 'end' lies.
void CastRay(const Eigen::Array2i& begin, const Eigen::Array2i& end,const std::vector<uint16>& miss_table,ProbabilityGrid* const probability_grid) {// For simplicity, we order 'begin' and 'end' by their x coordinate.if (begin.x() > end.x()) {CastRay(end, begin, miss_table, probability_grid);return;}CHECK_GE(begin.x(), 0);CHECK_GE(begin.y(), 0);CHECK_GE(end.y(), 0);// Special case: We have to draw a vertical line in full pixels, as 'begin'// and 'end' have the same full pixel x coordinate.if (begin.x() / kSubpixelScale == end.x() / kSubpixelScale) {Eigen::Array2i current(begin.x() / kSubpixelScale,std::min(begin.y(), end.y()) / kSubpixelScale);const int end_y = std::max(begin.y(), end.y()) / kSubpixelScale;for (; current.y() <= end_y; ++current.y()) {probability_grid->ApplyLookupTable(current, miss_table);}return;}const int64 dx = end.x() - begin.x();const int64 dy = end.y() - begin.y();const int64 denominator = 2 * kSubpixelScale * dx;// The current full pixel coordinates. We begin at 'begin'.Eigen::Array2i current = begin / kSubpixelScale;// To represent subpixel centers, we use a factor of 2 * 'kSubpixelScale' in// the denominator.// +-+-+-+ -- 1 = (2 * kSubpixelScale) / (2 * kSubpixelScale)// | | | |// +-+-+-+// | | | |// +-+-+-+ -- top edge of first subpixel = 2 / (2 * kSubpixelScale)// | | | | -- center of first subpixel = 1 / (2 * kSubpixelScale)// +-+-+-+ -- 0 = 0 / (2 * kSubpixelScale)// The center of the subpixel part of 'begin.y()' assuming the// 'denominator', i.e., sub_y / denominator is in (0, 1).int64 sub_y = (2 * (begin.y() % kSubpixelScale) + 1) * dx;// The distance from the from 'begin' to the right pixel border, to be divided// by 2 * 'kSubpixelScale'.const int first_pixel =2 * kSubpixelScale - 2 * (begin.x() % kSubpixelScale) - 1;// The same from the left pixel border to 'end'.const int last_pixel = 2 * (end.x() % kSubpixelScale) + 1;// The full pixel x coordinate of 'end'.const int end_x = std::max(begin.x(), end.x()) / kSubpixelScale;// Move from 'begin' to the next pixel border to the right.sub_y += dy * first_pixel;if (dy > 0) {while (true) {probability_grid->ApplyLookupTable(current, miss_table);while (sub_y > denominator) {sub_y -= denominator;++current.y();probability_grid->ApplyLookupTable(current, miss_table);}++current.x();if (sub_y == denominator) {sub_y -= denominator;++current.y();}if (current.x() == end_x) {break;}// Move from one pixel border to the next.sub_y += dy * 2 * kSubpixelScale;}// Move from the pixel border on the right to 'end'.sub_y += dy * last_pixel;probability_grid->ApplyLookupTable(current, miss_table);while (sub_y > denominator) {sub_y -= denominator;++current.y();probability_grid->ApplyLookupTable(current, miss_table);}CHECK_NE(sub_y, denominator);CHECK_EQ(current.y(), end.y() / kSubpixelScale);return;}// Same for lines non-ascending in y coordinates.while (true) {probability_grid->ApplyLookupTable(current, miss_table);while (sub_y < 0) {sub_y += denominator;--current.y();probability_grid->ApplyLookupTable(current, miss_table);}++current.x();if (sub_y == 0) {sub_y += denominator;--current.y();}if (current.x() == end_x) {break;}sub_y += dy * 2 * kSubpixelScale;}sub_y += dy * last_pixel;probability_grid->ApplyLookupTable(current, miss_table);while (sub_y < 0) {sub_y += denominator;--current.y();probability_grid->ApplyLookupTable(current, miss_table);}CHECK_NE(sub_y, 0);CHECK_EQ(current.y(), end.y() / kSubpixelScale);
}void GrowAsNeeded(const sensor::RangeData& range_data,ProbabilityGrid* const probability_grid) {Eigen::AlignedBox2f bounding_box(range_data.origin.head<2>());constexpr float kPadding = 1e-6f;for (const Eigen::Vector3f& hit : range_data.returns) {bounding_box.extend(hit.head<2>());}for (const Eigen::Vector3f& miss : range_data.misses) {bounding_box.extend(miss.head<2>());}probability_grid->GrowLimits(bounding_box.min() -kPadding * Eigen::Vector2f::Ones());probability_grid->GrowLimits(bounding_box.max() +kPadding * Eigen::Vector2f::Ones());
}

3.5 FinishUpdate()

cartographer/cartographer/mapping/2d/grid_2d.cc

// Finishes the update sequence.
void Grid2D::FinishUpdate() {while (!update_indices_.empty()) {DCHECK_GE(correspondence_cost_cells_[update_indices_.back()],kUpdateMarker);correspondence_cost_cells_[update_indices_.back()] -= kUpdateMarker;update_indices_.pop_back();}
}

4 map_limits.h

struct CellLimits {CellLimits() = default;CellLimits(int init_num_x_cells, int init_num_y_cells): num_x_cells(init_num_x_cells), num_y_cells(init_num_y_cells) {}explicit CellLimits(const proto::CellLimits& cell_limits): num_x_cells(cell_limits.num_x_cells()),num_y_cells(cell_limits.num_y_cells()) {}int num_x_cells = 0;int num_y_cells = 0;
};// Defines the limits of a grid map. This class must remain inlined for
// performance reasons.
class MapLimits {private:// Returns the cell size in meters. All cells are square and the resolution is the length of one side.double resolution_;   // Returns the corner of the limits, i.e., all pixels have positions with smaller coordinates.Eigen::Vector2d max_;  // Returns the limits of the grid in number of cells.CellLimits cell_limits_;
};

map_limits 记录了地图的各种信息,分辨率,物理世界坐标的最大值(左上角的栅格最大),栅格的x, y方向的格子数量。

max_ 为该栅格在物理世界中的坐标,不是栅格的坐标。

5 Grid2D

class Grid2D : public GridInterface {public:explicit Grid2D(const MapLimits& limits, float min_correspondence_cost,float max_correspondence_cost);explicit Grid2D(const proto::Grid2D& proto);// Returns the limits of this Grid2D.const MapLimits& limits() const { return limits_; }// Finishes the update sequence.void FinishUpdate();// Returns the correspondence cost of the cell with 'cell_index'.float GetCorrespondenceCost(const Eigen::Array2i& cell_index) const;// Returns the minimum possible correspondence cost.float GetMinCorrespondenceCost() const { return min_correspondence_cost_; }// Returns the maximum possible correspondence cost.float GetMaxCorrespondenceCost() const { return max_correspondence_cost_; }// Returns true if the probability at the specified index is known.bool IsKnown(const Eigen::Array2i& cell_index) const;// Fills in 'offset' and 'limits' to define a subregion of that contains all// known cells.void ComputeCroppedLimits(Eigen::Array2i* const offset,CellLimits* const limits) const;// Grows the map as necessary to include 'point'. This changes the meaning of// these coordinates going forward. This method must be called immediately// after 'FinishUpdate', before any calls to 'ApplyLookupTable'.virtual void GrowLimits(const Eigen::Vector2f& point);virtual std::unique_ptr<Grid2D> ComputeCroppedGrid() const = 0;virtual proto::Grid2D ToProto() const;virtual bool DrawToSubmapTexture(proto::SubmapQuery::Response::SubmapTexture* const texture,transform::Rigid3d local_pose) const = 0;protected:const std::vector<uint16>& correspondence_cost_cells() const {return correspondence_cost_cells_;}const std::vector<int>& update_indices() const { return update_indices_; }const Eigen::AlignedBox2i& known_cells_box() const {return known_cells_box_;}std::vector<uint16>* mutable_correspondence_cost_cells() {return &correspondence_cost_cells_;}std::vector<int>* mutable_update_indices() { return &update_indices_; }Eigen::AlignedBox2i* mutable_known_cells_box() { return &known_cells_box_; }// Converts a 'cell_index' into an index into 'cells_'.int ToFlatIndex(const Eigen::Array2i& cell_index) const;private:// 地图信息MapLimits limits_;// 栅格地图每个栅格的概率值std::vector<uint16> correspondence_cost_cells_; // 概率最小值,最大值float min_correspondence_cost_;float max_correspondence_cost_;// std::vector<int> update_indices_;// Bounding box of known cells to efficiently compute cropping limits.Eigen::AlignedBox2i known_cells_box_;
};

// Returns the correspondence cost of the cell with 'cell_index'.
float Grid2D::GetCorrespondenceCost(const Eigen::Array2i& cell_index) const {if (!limits().Contains(cell_index)) return kMaxCorrespondenceCost;return ValueToCorrespondenceCost(correspondence_cost_cells()[ToFlatIndex(cell_index)]);
}const std::vector<uint16>& correspondence_cost_cells() const {return correspondence_cost_cells_;}int Grid2D::ToFlatIndex(const Eigen::Array2i& cell_index) const {CHECK(limits_.Contains(cell_index)) << cell_index;return limits_.cell_limits().num_x_cells * cell_index.y() + cell_index.x();
}// Converts a uint16 (which may or may not have the update marker set) to a
// correspondence cost in the range [kMinCorrespondenceCost,
// kMaxCorrespondenceCost].
inline float ValueToCorrespondenceCost(const uint16 value) {return (*kValueToCorrespondenceCost)[value];
}const std::vector<float>* const kValueToCorrespondenceCost =PrecomputeValueToCorrespondenceCost().release();std::unique_ptr<std::vector<float>> PrecomputeValueToCorrespondenceCost() {return PrecomputeValueToBoundedFloat(kUnknownCorrespondenceValue, kMaxCorrespondenceCost,kMinCorrespondenceCost, kMaxCorrespondenceCost);
}std::unique_ptr<std::vector<float>> PrecomputeValueToBoundedFloat(const uint16 unknown_value, const float unknown_result,const float lower_bound, const float upper_bound) {auto result = common::make_unique<std::vector<float>>();// Repeat two times, so that both values with and without the update marker// can be converted to a probability.for (int repeat = 0; repeat != 2; ++repeat) {for (int value = 0; value != 32768; ++value) {result->push_back(SlowValueToBoundedFloat(value, unknown_value, unknown_result, lower_bound, upper_bound));}}return result;
}// 0 is unknown, [1, 32767] maps to [lower_bound, upper_bound].
float SlowValueToBoundedFloat(const uint16 value, const uint16 unknown_value,const float unknown_result,const float lower_bound,const float upper_bound) {CHECK_GE(value, 0);CHECK_LE(value, 32767);if (value == unknown_value) return unknown_result;const float kScale = (upper_bound - lower_bound) / 32766.f;return value * kScale + (lower_bound - kScale);
}

REFERENCES

cartographer 生成子图 https://blog.csdn.net/xiaoma_bk/article/details/83063389

查找表与占用栅格更新 http://gaoyichao.com/Xiaotu/?book=Cartographer%E6%BA%90%E7%A0%81%E8%A7%A3%E8%AF%BB&title=%E6%9F%A5%E6%89%BE%E8%A1%A8%E4%B8%8E%E5%8D%A0%E7%94%A8%E6%A0%85%E6%A0%BC%E6%9B%B4%E6%96%B0

cartographer探秘第四章之代码解析(八) --- 生成地图相关推荐

  1. 学习笔记-第十四章 恶意代码分析实战

    第十四章 恶意代码的网络特征 1.网络应对措施. 网络行为的基本属性包括IP地址,TCP端口,以及流量内容等,网络和安全 设备可以利用它们,来提供网络应对措施.根据IP地址和端口,防火墙和路由器可以限 ...

  2. 第四章 PX4-Pixhawk-MPU6000传感器驱动解析

    第四章MPU6000传感器驱动解析 Mpu6000是一个3轴加速度和3轴陀螺仪传感器,这一章节我们将对MPU6000这个传感器进行解析,依照这个解析步骤同样可以对L3GD20(3轴陀螺仪).HMC58 ...

  3. 第四章MPU6000传感器驱动解析

    版权声明:本文为博主原创文章,未经博主允许不得转载. 第四章MPU6000传感器驱动解析 Mpu6000是一个3轴加速度和3轴陀螺仪传感器,这一章节我们将对MPU6000这个传感器进行解析,依照这个解 ...

  4. CodeCombat代码全记录(Python学习利器)--安息之云山峰(第四章)代码1

    我们已经有了前三章的基础了,到了第四章,你会发现提示少之又少了.这时,我们大都要靠自己了!!!加油!!如果你没有思路,请仔细看下装备的说明,毕竟到了这关,你需要购买好多其他的新装备,而新装备中存在了新 ...

  5. c语言八数码A星算法代码解析,八数码问题c语言a星算法详细实验报告含代码解析...

    八数码问题c语言a星算法详细实验报告含代码解析 (13页) 本资源提供全文预览,点击全文预览即可全文预览,如果喜欢文档就下载吧,查找使用更方便哦! 14.9 积分 一.实验内容和要求 八数码问题:在3 ...

  6. Paxos算法之旅(四)zookeeper代码解析--转载

    ZooKeeper是近期比较热门的一个类Paxos实现.也是一个逐渐得到广泛应用的开源的分布式锁服务实现.被认为是Chubby的开源版,虽然具体实现有很多差异.ZooKeeper概要的介绍可以看官方文 ...

  7. 一个基于JRTPLIB的轻量级RTSP客户端(myRTSPClient)——收流篇:(四)example代码解析...

    --------------------更新2018.08.20------------------- 添加http_tunnel_example.cpp作为RtspOverHttp示例程序. --- ...

  8. 视觉SLAM十四讲CH10代码解析及课后习题详解

    g2o_viewer问题解决 在进行位姿图优化时候,如果出现g2o_viewer: command not found,说明你的g2o_viewer并没有安装上,打开你之前安装的g2o文件夹,打开bi ...

  9. 视觉SLAM十四讲CH8代码解析及课后习题详解

    第一版的代码: direct_semidense.cpp #include <iostream> #include <fstream> #include <list> ...

  10. CE教程 第四章 《代码寻找》

    步骤 5: 代码寻找 (密码=888899) 有时一些东西的保存位置在你重新开始游戏时会改变,甚至是在你玩的时候也会变,在这种情况下,你 用2步仍然能做出可以用的内存列表. 在这一步会说明怎样用寻找代 ...

最新文章

  1. 如何在 Linux 上用密码加密和解密文件
  2. 云计算之路:数据库迁移方案
  3. Javascript元编程创建DOM节点
  4. python可以在excel中应用吗,python怎样在excel中应用?-Python教程
  5. 算法 --- 删除数组中重复项
  6. 解决问题SyntaxError: Unexpected token import
  7. C语言 · 芯片测试
  8. Phonegap 环境配置
  9. 力扣914.卡牌分组
  10. PCL教程-PCLVisualizer可视化类的使用
  11. Android OpenGL ES 学习(十一) –渲染YUV视频以及视频抖音特效
  12. 图像算法工程师岗位的主要职责(合集)
  13. 微软的奥尔良项目简介
  14. 各串口设备节点/dev/tty* 的区别
  15. Java实现远程主机唤醒 (WOL)
  16. Android Studio 一键切换界面风格
  17. vrops vRealize Operations Manager 8云管平台部署与配置
  18. 关于Arduino图形化编程插件ArduBlock的安装方法
  19. H5页面实现下载文件兼容移动端
  20. DMS、RDS、OLAP简介

热门文章

  1. Mysql表设计需要注意的问题
  2. JVM调优总结(转载)
  3. SDOI2018 旧试题
  4. bootstrap基础样式学习(一)
  5. 实验吧—Web——WP之 Forms
  6. ExtJS4.2学习(13)基于表格的扩展插件---rowEditing
  7. 央行超级网银8月上线 第三方支付平台或暂停接入
  8. [软件更新]迅雷(Thunder)5.9.2.927版本发布
  9. 帧中继环境下Ping的实现
  10. clamp.js 的使用---超出省略 (翻译)