Skip to content

Commit

Permalink
update comment
Browse files Browse the repository at this point in the history
  • Loading branch information
lixiang committed Jul 8, 2021
1 parent 8652117 commit ff4756a
Show file tree
Hide file tree
Showing 12 changed files with 131 additions and 75 deletions.
2 changes: 2 additions & 0 deletions catkin_make.sh
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#!/bin/bash

catkin_make_isolated --install --use-ninja

#catkin_make_isolated --install --use-ninja -DCMAKE_EXPORT_COMPILE_COMMANDS=Yes


source install_isolated/setup.bash
Binary file added error_log.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ bool FixedRatioSampler::Pulse() {
++num_samples_;
return true;
}
// 返回false时代表数据可以不用,可以跳过计算
return false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,15 +91,9 @@ void CollatedTrajectoryBuilder::HandleCollatedSensorData(
const std::string& sensor_id, std::unique_ptr<sensor::Data> data) {
auto it = rate_timers_.find(sensor_id);
if (it == rate_timers_.end()) {

// c++11: map::emplace() 用于通过在容器中插入新元素来扩展map容器.
// 元素是直接构建的(既不复制也不移动).仅当键不存在时才进行插入
// 它返回一个布尔对, emplace().first表示新插入元素或者原始位置的迭代器, emplace().second表示是否发生插入

// c++11: std::piecewise_construct 分次生成tuple的标志常量, 不加就报错
// c++11: std::forward_as_tuple tuple的完美转发
// 该 tuple 在以右值为参数时拥有右值引用数据成员, 否则拥有左值引用数据成员

// map::emplace()返回一个pair
// emplace().first表示新插入元素或者原始位置的迭代器
// emplace().second表示插入成功,只有在key在map中不存在时才插入成功
it = rate_timers_
.emplace(
std::piecewise_construct,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,13 +78,13 @@ class MapBuilderBridge {
std::shared_ptr<const LocalSlamData> local_slam_data;
cartographer::transform::Rigid3d local_to_map; // local frame 到 global frame间的坐标变换

// c++11: std::shared_ptr 主要的用途就是方便资源的管理, 自动释放没有指针引用的资源
// 使用引用计数来标识是否有其余指针指向该资源.(注意, shart_ptr本身指针会占1个引用)
// 引用计数是分配在动态分配的, std::shared_ptr支持拷贝, 新的指针获可以获取前引用计数个数

// published_frame 到 tracking_frame 间的坐标变换
std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
TrajectoryOptions trajectory_options;

// c++11: std::shared_ptr 主要的用途就是方便资源的管理, 自动释放没有指针引用的资源
// 使用引用计数来标识是否有其余指针指向该资源.(注意, shart_ptr本身指针会占1个引用)
// 引用计数是分配在动态分配的, std::shared_ptr支持拷贝, 新的指针获可以获取前引用计数个数
};

MapBuilderBridge(
Expand Down
95 changes: 71 additions & 24 deletions src/cartographer_ros/cartographer_ros/cartographer_ros/node.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ namespace {

// c++11: lambda表达式
/*
* tag: 这块放课件里
[外部变量访问方式说明符 = & ] (参数表) -> 返回值类型
{
语句块
Expand All @@ -86,17 +87,39 @@ const Rigid3d tracking_to_local = [&] {
// Subscribes to the 'topic' for 'trajectory_id' using the 'node_handle' and
// calls 'handler' on the 'node' to handle messages. Returns the subscriber.

// ?: 不清楚 Node::*handler 的用法, 大致是句柄的功能
// *handler可能来自于 /usr/include/x11/Xlibint.h
// Bool (*handler)(
// Display* /* dpy */,
// xReply* /* rep */,
// char* /* buf */,
// int /* len */,
// XPointer /* data */
// );

// 目的就是在node_handle中订阅topic,并注册回调函数
/*
* tag: 这块放课件里
int function(int a, int b)
{
// 执行代码
}
int main(void)
{
int (*FP)(int, int); // 函数指针的声明方式
FP= function; // 第一种赋值方法
// FP = &function; // 第二种赋值方法
FP(1,2); // 第一种调用方法
// (*FP)(1,2); // 第二种调用方法
student stu(12, "guyanhun");
void (student::*p)(); // 外部声明类内函数的函数指针
(stu.*p)(); // 外部调用该函数指针
return 0;
}
*/

/**
* @brief 在node_handle中订阅topic,并与传入的回调函数进行注册
*
* @tparam MessageType 模板参数,消息的数据类型
* @param[in] handler 函数指针, 接受传入的函数的地址
* @param[in] trajectory_id 轨迹id
* @param[in] topic 订阅的topic名字
* @param[in] node_handle ros的node_handle
* @param[in] node node类的指针
* @return ::ros::Subscriber 订阅者
*/
template <typename MessageType>
::ros::Subscriber SubscribeWithHandler(
void (Node::*handler)(int, const std::string&,
Expand All @@ -108,8 +131,8 @@ ::ros::Subscriber SubscribeWithHandler(
topic, kInfiniteSubscriberQueueSize, // kInfiniteSubscriberQueueSize = 0
// 使用boost::function构造回调函数,被subscribe注册
boost::function<void(const typename MessageType::ConstPtr&)>(
[node, handler, trajectory_id,
topic](const typename MessageType::ConstPtr& msg) {
// c++11: lambda表达式
[node, handler, trajectory_id, topic](const typename MessageType::ConstPtr& msg) {
(node->*handler)(trajectory_id, topic, msg);
}));
}
Expand Down Expand Up @@ -302,13 +325,18 @@ void Node::AddExtrapolator(const int trajectory_id,
: options.trajectory_builder_options.trajectory_builder_2d_options()
.imu_gravity_time_constant();

// c++11: std::forward_as_tuple(): 用于接收右值引用数据生成tuple
// c++11: std::piecewise_construct: 分段构造常量, 将此常量值作为构造对象的第一个参数传递
// 以选择构造函数形式, 该形式通过将两个元组对象的元素转发到其各自的构造函数来就地构造其成员.
// c++11: map::emplace() 用于通过在容器中插入新元素来扩展map容器
// 元素是直接构建的(既不复制也不移动).仅当键不存在时才进行插入
// c++11: std::forward_as_tuple tuple的完美转发
// 该 tuple 在以右值为参数时拥有右值引用数据成员, 否则拥有左值引用数据成员
// c++11: std::piecewise_construct 分次生成tuple的标志常量
// 在map::emplace()中使用forward_as_tuple时必须要加piecewise_construct,不加就报错
// https://www.cnblogs.com/guxuanqing/p/11396511.html

// 以1ms, 以及重力常数10, 作为参数构造PoseExtrapolator
extrapolators_.emplace(
std::piecewise_construct, std::forward_as_tuple(trajectory_id),
std::piecewise_construct,
std::forward_as_tuple(trajectory_id),
std::forward_as_tuple(
::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
gravity_time_constant));
Expand All @@ -324,15 +352,18 @@ void Node::AddSensorSamplers(const int trajectory_id,
const TrajectoryOptions& options) {
CHECK(sensor_samplers_.count(trajectory_id) == 0);
sensor_samplers_.emplace(
std::piecewise_construct, std::forward_as_tuple(trajectory_id),
std::piecewise_construct,
std::forward_as_tuple(trajectory_id),
std::forward_as_tuple(
options.rangefinder_sampling_ratio, options.odometry_sampling_ratio,
options.fixed_frame_pose_sampling_ratio, options.imu_sampling_ratio,
options.rangefinder_sampling_ratio,
options.odometry_sampling_ratio,
options.fixed_frame_pose_sampling_ratio,
options.imu_sampling_ratio,
options.landmarks_sampling_ratio));
}

/**
* @brief 每5e-3s发布一次轨迹数据以及tf
* @brief 每5e-3s发布一次tf与tracked_pose
*
* @param[in] timer_event
*/
Expand Down Expand Up @@ -649,6 +680,7 @@ void Node::LaunchSubscribers(const TrajectoryOptions& options,
&node_handle_, this),
topic});
}

// point_clouds 的订阅与注册回调函数
for (const std::string& topic :
ComputeRepeatedTopicNames(kPointCloud2Topic, options.num_point_clouds)) {
Expand Down Expand Up @@ -695,8 +727,11 @@ void Node::LaunchSubscribers(const TrajectoryOptions& options,
if (options.use_landmarks) {
subscribers_[trajectory_id].push_back(
{SubscribeWithHandler<cartographer_ros_msgs::LandmarkList>(
&Node::HandleLandmarkMessage, trajectory_id, kLandmarkTopic,
&node_handle_, this),
&Node::HandleLandmarkMessage,
trajectory_id,
kLandmarkTopic,
&node_handle_,
this),
kLandmarkTopic});
}
}
Expand Down Expand Up @@ -1224,7 +1259,7 @@ void Node::MaybeWarnAboutTopicMismatch(
int trajectory_id = entry.first;
for (const auto& subscriber : entry.second) {

// 获取设置的topic名字
// 获取实际订阅的topic名字
std::string resolved_topic = node_handle_.resolveName(subscriber.topic);

// 如果设置的topic名字,在ros中不存在,则报错
Expand All @@ -1234,6 +1269,18 @@ void Node::MaybeWarnAboutTopicMismatch(
<< " (resolved topic \"" << resolved_topic << "\")"
<< " but no publisher is currently active.";
print_topics = true;

// tag: 把报错信息放课件里
/*
[ INFO] [1625724722.715674522]: I0708 14:12:02.000000 20138 map_builder_bridge.cc:153] Added trajectory with ID '0'.
[ WARN] [1625724725.726943013]: W0708 14:12:05.000000 20138 node.cc:1267] Expected topic "points2" (trajectory 0) (resolved topic "/points2") but no publisher is currently active.
[ WARN] [1625724725.727046746]: W0708 14:12:05.000000 20138 node.cc:1267] Expected topic "imu" (trajectory 0) (resolved topic "/imu") but no publisher is currently active.
[ WARN] [1625724725.727145643]: W0708 14:12:05.000000 20138 node.cc:1280] Currently available topics are: /constraint_list,/submap_list,/scan_matched_points2,/rosout,/tf,/clock,/rosout_agg,/map,/trajectory_node_list,/landmark_poses_list,
[ WARN] [1625724739.386545399, 1606808654.481099623]: W0708 14:12:19.000000 20138 ordered_multi_queue.cc:232] Queue waiting for data: (0, points2)
[ WARN] [1625724739.994835822, 1606808655.086546848]: W0708 14:12:19.000000 20138 ordered_multi_queue.cc:232] Queue waiting for data: (0, points2)
[ WARN] [1625724740.588885518, 1606808655.682104741]: W0708 14:12:20.000000 20138 ordered_multi_queue.cc:232] Queue waiting for data: (0, points2)
[ WARN] [1625724741.195557158, 1606808656.288400347]: W0708 14:12:21.000000 20138 ordered_multi_queue.cc:232] Queue waiting for data: (0, points2)
*/
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@

namespace cartographer_ros {

//

/**
* @brief 如果只有一个传感器, 那订阅的topic就是topic,
* 如果是多个传感器, 那订阅的topic就是topic_1,topic_2
Expand All @@ -41,6 +39,7 @@ std::vector<std::string> ComputeRepeatedTopicNames(const std::string& topic,
for (int i = 0; i < num_topics; ++i) {
topics.emplace_back(topic + "_" + std::to_string(i + 1));
}
// num_topics要是0就返回空的vector
return topics;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
namespace cartographer_ros {

// Default topic names; expected to be remapped as needed.
// 固定的topic与service的名字, 可以通过launch里的remap来更改
// 固定的topic与service的名字, Topic名字可以通过launch里的remap来更改
constexpr char kLaserScanTopic[] = "scan";
constexpr char kMultiEchoLaserScanTopic[] = "echoes";
constexpr char kPointCloud2Topic[] = "points2";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,9 @@ Panels:
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Submaps1
- /PointCloud21
Splitter Ratio: 0.600670993
Tree Height: 767
Expanded: ~
Splitter Ratio: 0.544444442
Tree Height: 463
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand All @@ -33,7 +31,7 @@ Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Cell Size: 5
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Expand Down Expand Up @@ -88,22 +86,6 @@ Visualization Manager:
{}
Update Interval: 0
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: Submaps
Enabled: true
Fade-out distance: 1
Expand All @@ -115,7 +97,18 @@ Visualization Manager:
All: true
All Submap Pose Markers: true
Trajectory 0:
0.42: true
0.160: true
1.160: true
10.156: true
11.76: true
2.160: true
3.160: true
4.160: true
5.160: true
6.160: true
7.160: true
8.160: true
9.160: true
Submap Pose Markers: true
Value: true
Topic: /submap_list
Expand Down Expand Up @@ -181,6 +174,23 @@ Visualization Manager:
Intra residuals: true
Queue Size: 100
Value: true
- Alpha: 1
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: false
Name: Map
Topic: /map
Unreliable: false
Use Timestamp: false
Value: false
- Class: rviz/Axes
Enabled: true
Length: 2
Name: Axes
Radius: 0.100000001
Reference Frame: front_laser_link
Value: true
Enabled: true
Global Options:
Background Color: 100; 100; 100
Expand All @@ -205,7 +215,7 @@ Visualization Manager:
Value: true
Views:
Current:
Angle: 0
Angle: 0.174999982
Class: rviz/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Expand All @@ -215,27 +225,27 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Scale: 10
Scale: 10.3141413
Target Frame: <Fixed Frame>
Value: TopDownOrtho (rviz)
X: 0
Y: 0
X: -19.0468502
Y: -2.51346016
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1053
Height: 744
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001c500000391fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000391000000e000fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000391fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000391000000b500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007350000003efc0100000002fb0000000800540069006d00650100000000000007350000035200fffffffb0000000800540069006d00650100000000000004500000000000000000000004550000039100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000025efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000025e000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000025efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005150000003efc0100000002fb0000000800540069006d00650100000000000005150000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a50000025e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1845
X: 75
Y: 27
collapsed: true
Width: 1301
X: 65
Y: 24
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ options = {
-- 如果为false tf树为map->footprint
publish_frame_projected_to_2d = false, -- 是否将坐标系投影到平面上

use_pose_extrapolator = false, -- 发布tf时是使用pose_extrapolator的位姿还是前端计算出来的位姿

use_odometry = false, -- 是否使用里程计,如果使用要求一定要有odom的tf
use_nav_sat = false, -- 是否使用gps
use_landmarks = false, -- 是否使用landmark
Expand Down
Loading

0 comments on commit ff4756a

Please sign in to comment.