Skip to content

Commit 9d6a186

Browse files
committed
Use the camera as the base type
1 parent ead0481 commit 9d6a186

File tree

14 files changed

+187
-127
lines changed

14 files changed

+187
-127
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ endif ()
1313
add_subdirectory(infinite_sense_core)
1414

1515
add_executable(${PROJECT_NAME}_zmq_node
16-
example/ZMQ/zmq_main.cpp
16+
example/ZMQ/main.cpp
1717
)
1818
target_link_libraries(${PROJECT_NAME}_zmq_node PRIVATE
1919
infinite_sense_core
Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
1-
#include "cam.h"
1+
#include "mvcam.h"
22
#include "infinite_sense.h"
33
#include "MvCameraControl.h"
4-
#include "log.h"
5-
#include "trigger.h"
64
namespace infinite_sense {
75
bool IsColor(const MvGvspPixelType type) {
86
switch (type) {

example/GigeCam/mvcam.h

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
#pragma once
2+
#include "infinite_sense.h"
3+
namespace infinite_sense {
4+
class CamManger final : public Cam {
5+
public:
6+
explicit CamManger(const std::map<std::string, TriggerDevice>& params) : params_(params) {}
7+
~CamManger() override;
8+
9+
CamManger(const CamManger&) = delete;
10+
CamManger& operator=(const CamManger&) = delete;
11+
12+
bool Initialization() override;
13+
void Stop() override;
14+
void Start() override;
15+
void Restart() override;
16+
17+
private:
18+
void Receive(void* handle, const std::string&) override;
19+
bool is_running_{false};
20+
std::vector<int> rets_;
21+
std::vector<void*> handles_;
22+
std::vector<std::thread> cam_threads_;
23+
std::map<std::string, TriggerDevice> params_;
24+
};
25+
} // namespace infinite_sense

example/ZMQ/main.cpp

Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
#include "infinite_sense.h"
2+
using namespace infinite_sense;
3+
int main() {
4+
5+
// 1.创建同步器
6+
Synchronizer synchronizer;
7+
/*
8+
使用网口连接
9+
synchronizer.SetNetLink("192.168.1.188", 8888);
10+
*/
11+
synchronizer.SetUsbLink("/dev/ttyACM0", 460800);
12+
13+
/*
14+
如使用工业相机, 需要指定 相机名称 和 同步板的触发端口
15+
std::map<std::string, TriggerDevice> params;
16+
params["camera_1"] = TriggerDevice::CAM_1; //camera_1:表示设备的名称,TriggerDevice::CAM_1:使用同步板CAM_1端口触发
17+
synchronizer.UseMvCam(params);
18+
*/
19+
20+
// 2.开启同步
21+
synchronizer.Start();
22+
23+
// 3.订阅数据
24+
Synchronizer::PrintSummary();
25+
zmq::context_t context(1);
26+
zmq::socket_t subscriber(context, zmq::socket_type::sub);
27+
subscriber.connect("tcp://localhost:5555");
28+
29+
const std::string topic = "imu_1"; // 订阅特定主题(如,板载IMU数据: "imu_1")
30+
subscriber.setsockopt(ZMQ_SUBSCRIBE, topic.c_str(), topic.size());
31+
zmq::message_t msg;
32+
while (true) {
33+
if (subscriber.recv(msg, zmq::recv_flags::dontwait)) {
34+
if (subscriber.get(zmq::sockopt::rcvmore)) {
35+
zmq::message_t dummy;
36+
subscriber.recv(dummy);
37+
}
38+
}
39+
}
40+
// 4.停止同步
41+
synchronizer.Stop();
42+
return 0;
43+
}

infinite_sense_core/CMakeLists.txt

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,13 +24,10 @@ add_library(${PROJECT_NAME} SHARED
2424
src/infinite_sense.cpp
2525
src/trigger.cpp
2626
src/usb.cpp
27-
src/cam.cpp
2827
src/image.cpp
2928
src/net.cpp
3029
src/messenger.cpp
3130
src/ptp.cpp
32-
include/ptp.h
33-
src/sensor.h
3431
)
3532
# 检测平台并设置相关变量
3633
if (CMAKE_SYSTEM_PROCESSOR MATCHES "arm" OR CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64")

infinite_sense_core/include/cam.h

Lines changed: 14 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -4,27 +4,26 @@
44
#include "messenger.h"
55
#include "infinite_sense.h"
66
namespace infinite_sense {
7-
class CamManger {
8-
public:
9-
explicit CamManger(const std::map<std::string, TriggerDevice>& params) : params_(params) {}
10-
~CamManger();
7+
class Cam{
8+
public:
9+
Cam();
10+
explicit Cam(const std::map<std::string, TriggerDevice>& params) : params_(params) {}
11+
virtual ~Cam();
1112

12-
CamManger(const CamManger&) = delete;
13-
CamManger& operator=(const CamManger&) = delete;
13+
Cam(const Cam&) = delete;
14+
Cam& operator=(const Cam&) = delete;
1415

15-
bool Initialization();
16-
void Stop();
17-
void Start();
16+
virtual bool Initialization();
17+
virtual void Stop();
18+
virtual void Start();
19+
virtual void Restart();
1820
void Enable() { is_running_ = true; }
1921
void Disable() { is_running_ = false; }
20-
void Restart();
21-
22-
private:
23-
void Receive(void* handle, const std::string&);
22+
private:
23+
virtual void Receive(void* handle, const std::string&);
2424
bool is_running_{false};
25-
std::vector<int> rets_;
26-
std::vector<void*> handles_;
2725
std::vector<std::thread> cam_threads_;
2826
std::map<std::string, TriggerDevice> params_;
2927
};
28+
3029
} // namespace infinite_sense
Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
#pragma once
2+
#include <cstdint>
3+
#include <string>
4+
#include "image.h"
5+
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+
};
14+
15+
struct CamData {
16+
uint64_t time_stamp_us;
17+
std::string name;
18+
GMat image;
19+
};
20+
21+
struct LaserData {
22+
uint64_t time_stamp_us;
23+
std::string name;
24+
};
25+
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+
};
34+
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/data.h

Lines changed: 50 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -1,45 +1,60 @@
11
#pragma once
2-
#include <cstdint>
3-
#include <string>
4-
#include "image.h"
2+
#include "infinite_sense.h"
3+
54
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-
};
145

15-
struct CamData {
16-
uint64_t time_stamp_us;
17-
std::string name;
18-
GMat image;
6+
inline void ProcessTriggerData(const nlohmann::json &data) {
7+
if (data["f"] != "t") {
8+
return;
9+
}
10+
const uint64_t time_stamp = data["t"];
11+
const uint16_t status = data["s"];
12+
const uint64_t count =data["c"];
13+
SET_LAST_TRIGGER_STATUS(time_stamp, status);
1914
};
2015

21-
struct LaserData {
22-
uint64_t time_stamp_us;
23-
std::string name;
16+
inline void ProcessIMUData(const nlohmann::json &data) {
17+
if (data["f"] != "imu") {
18+
return;
19+
}
20+
ImuData imu{};
21+
const uint64_t time_stamp = data["t"];
22+
const uint64_t count = data["c"];
23+
imu.time_stamp_us = time_stamp;
24+
// std::cout << imu.time_stamp_us << std::endl;
25+
imu.a[0] = data["d"][0];
26+
imu.a[1] = data["d"][1];
27+
imu.a[2] = data["d"][2];
28+
imu.g[0] = data["d"][3];
29+
imu.g[1] = data["d"][4];
30+
imu.g[2] = data["d"][5];
31+
imu.temperature = data["d"][6];
32+
imu.q[0] = data["q"][0];
33+
imu.q[1] = data["q"][1];
34+
imu.q[2] = data["q"][2];
35+
imu.q[3] = data["q"][3];
36+
Messenger::GetInstance().PubStruct("imu1",&imu,sizeof(imu));
2437
};
2538

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;
39+
inline void ProcessGPSData(const nlohmann::json &data) {
40+
if (data["f"] != "GNGGA") {
41+
return;
42+
}
43+
GPSData gps{};
44+
gps.latitude = data["d"][0];
45+
gps.longitude = data["d"][1];
46+
gps.gps_stamp_us = data["d"][2];
47+
gps.gps_stamp_us_trigger = data["d"][3];
48+
gps.time_stamp_us = data["t"];
49+
Messenger::GetInstance().PubStruct("gps",&gps,sizeof(gps));
3350
};
3451

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
52+
53+
inline void ProcessLOGData(const nlohmann::json &data) {
54+
if (data["f"] != "log") {
55+
return;
56+
}
57+
LOG(data["l"]) << data["msg"];
4458
};
45-
} // namespace infinite_sense
59+
60+
} // namespace infinite_sense

infinite_sense_core/include/infinite_sense.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,16 @@
11
#pragma once
22
#include "log.h"
3-
#include "data.h"
3+
#include "config.h"
44
#include "messenger.h"
5-
5+
#include "cam.h"
6+
#include "trigger.h"
67
namespace infinite_sense {
78

89
class NetManager;
910
class UsbManager;
1011
class CamManger;
1112
class TriggerManger;
1213
class Messenger;
13-
1414
/**
1515
* @class Synchronizer
1616
* @brief 同步器类,负责统一协调网络、串口、相机等模块的启动与配置,管理多传感器系统的时间同步。
@@ -59,7 +59,7 @@ class Synchronizer {
5959
void SetNetLink(std::string net_dev, unsigned int port);
6060

6161
/**
62-
* @brief 使用 MV(迈德威视)相机,并配置其对应的触发设备。
62+
* @brief 使用工业相机,并配置其对应的触发设备。
6363
*
6464
* @param params 可选参数:映射相机名称到 TriggerDevice 枚举。
6565
*/
@@ -100,7 +100,7 @@ class Synchronizer {
100100
std::shared_ptr<UsbManager> serial_manager_{nullptr};
101101

102102
/// 相机管理器
103-
std::shared_ptr<CamManger> cam_manager_{nullptr};
103+
std::shared_ptr<Cam> cam_manager_{nullptr};
104104
};
105105

106106
} // namespace infinite_sense

0 commit comments

Comments
 (0)