Skip to content

Commit 4539860

Browse files
committed
Add some notes
1 parent 6b6d87b commit 4539860

4 files changed

Lines changed: 111 additions & 40 deletions

File tree

infinite_sense_core/include/data.h

Lines changed: 36 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -3,43 +3,43 @@
33
#include <string>
44
#include "image.h"
55
namespace infinite_sense {
6-
struct ImuData {
7-
uint64_t time_stamp_us;
8-
float temperature;
9-
std::string name;
10-
float a[3];
11-
float g[3];
12-
float q[4];
13-
};
6+
struct ImuData {
7+
uint64_t time_stamp_us;
8+
float temperature;
9+
std::string name;
10+
float a[3];
11+
float g[3];
12+
float q[4];
13+
};
1414

15-
struct CamData {
16-
uint64_t time_stamp_us;
17-
std::string name;
18-
GMat image;
19-
};
15+
struct CamData {
16+
uint64_t time_stamp_us;
17+
std::string name;
18+
GMat image;
19+
};
2020

21-
struct LaserData {
22-
uint64_t time_stamp_us;
23-
std::string name;
24-
};
21+
struct LaserData {
22+
uint64_t time_stamp_us;
23+
std::string name;
24+
};
2525

26-
struct GPSData {
27-
uint64_t time_stamp_us;
28-
uint64_t gps_stamp_us;
29-
uint64_t gps_stamp_us_trigger;
30-
std::string name;
31-
float latitude;
32-
float longitude;
33-
};
26+
struct GPSData {
27+
uint64_t time_stamp_us;
28+
uint64_t gps_stamp_us;
29+
uint64_t gps_stamp_us_trigger;
30+
std::string name;
31+
float latitude;
32+
float longitude;
33+
};
3434

35-
enum TriggerDevice {
36-
IMU_1 = 0, // internal imu
37-
IMU_2 = 1, // external imu
38-
CAM_1 = 2, // camera 1
39-
CAM_2 = 3, // camera 2
40-
CAM_3 = 4, // camera 3
41-
CAM_4 = 5, // camera 4
42-
LASER = 6, // laser pps
43-
GPS = 7, // gps pps
44-
};
45-
}
35+
enum TriggerDevice {
36+
IMU_1 = 0, // internal imu
37+
IMU_2 = 1, // external imu
38+
CAM_1 = 2, // camera 1
39+
CAM_2 = 3, // camera 2
40+
CAM_3 = 4, // camera 3
41+
CAM_4 = 5, // camera 4
42+
LASER = 6, // laser pps
43+
GPS = 7, // gps pps
44+
};
45+
} // namespace infinite_sense

infinite_sense_core/include/image.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,8 @@ class GMat {
104104
public:
105105
GMat();
106106

107-
GMat(int rows_, int cols_, int type = GMatType<>::Type, uchar* src = nullptr, bool copy = false, int image_align = 16);
107+
GMat(int rows_, int cols_, int type = GMatType<>::Type, uchar* src = nullptr, bool copy = false,
108+
int image_align = 16);
108109

109110
GMat(const GMat& ref);
110111

infinite_sense_core/include/infinite_sense.h

Lines changed: 73 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,25 +10,96 @@ class SerialManager;
1010
class CamManger;
1111
class TriggerManger;
1212
class Messenger;
13+
14+
/**
15+
* @class Synchronizer
16+
* @brief 同步器类,负责统一协调网络、串口、相机等模块的启动与配置,管理多传感器系统的时间同步。
17+
*/
1318
class Synchronizer {
1419
public:
20+
/**
21+
* @brief 构造函数,初始化成员变量。
22+
*/
1523
Synchronizer();
24+
25+
/// 默认析构函数。
1626
~Synchronizer() = default;
27+
28+
/**
29+
* @brief 启动同步器,初始化并启动各组件(网络、串口、相机等)。
30+
*/
1731
void Start() const;
32+
33+
/**
34+
* @brief 停止同步器,释放资源。
35+
*/
1836
void Stop() const;
19-
static void SetLogPath(const std::string &path);
37+
38+
/**
39+
* @brief 设置日志输出路径(静态方法)。
40+
*
41+
* @param path 日志保存路径。
42+
*/
43+
static void SetLogPath(const std::string& path);
44+
45+
/**
46+
* @brief 配置串口连接参数。
47+
*
48+
* @param serial_dev 串口设备名称(如 "/dev/ttyUSB0")。
49+
* @param serial_baud_rate 波特率(如 115200)。
50+
*/
2051
void SetSerialLink(std::string serial_dev, int serial_baud_rate);
52+
53+
/**
54+
* @brief 配置网络连接参数。
55+
*
56+
* @param net_dev 目标网络 IP 地址。
57+
* @param port 网络端口号。
58+
*/
2159
void SetNetLink(std::string net_dev, unsigned int port);
60+
61+
/**
62+
* @brief 使用 MV(迈德威视)相机,并配置其对应的触发设备。
63+
*
64+
* @param params 可选参数:映射相机名称到 TriggerDevice 枚举。
65+
*/
2266
void UseMvCam(const std::map<std::string, TriggerDevice>& params = std::map<std::string, TriggerDevice>());
67+
68+
/**
69+
* @brief 获取指定设备最近一次的触发时间(静态方法)。
70+
*
71+
* @param dev 查询的设备类型。
72+
* @param time 返回对应的触发时间戳。
73+
* @return true 如果查询成功(设备有触发记录)。
74+
* @return false 如果设备无记录。
75+
*/
2376
static bool GetLastTriggerTime(TriggerDevice dev, uint64_t time);
24-
static void PrintSummary() ;
77+
78+
/**
79+
* @brief 打印当前系统的配置与状态摘要信息。
80+
*/
81+
static void PrintSummary();
82+
2583
private:
84+
/// 网络地址
2685
std::string net_ip_;
86+
87+
/// 网络端口号
2788
unsigned short net_port_{};
89+
90+
/// 串口设备
2891
std::string serial_dev_;
92+
93+
/// 串口波特率
2994
int serial_baud_rate_{};
95+
96+
/// 网络管理器
3097
std::shared_ptr<NetManager> net_manager_{nullptr};
98+
99+
/// 串口管理器
31100
std::shared_ptr<SerialManager> serial_manager_{nullptr};
101+
102+
/// 相机管理器
32103
std::shared_ptr<CamManger> cam_manager_{nullptr};
33104
};
34105

infinite_sense_core/src/ser.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,6 @@ void SerialManager::Receive() const {
6868
if (json_data.empty()) {
6969
continue;
7070
}
71-
// std::cout << json_data.dump() << std::endl;
7271
ptp_->ReceivePtpData(json_data);
7372
ProcessTriggerData(json_data);
7473
ProcessIMUData(json_data);

0 commit comments

Comments
 (0)