Skip to content

Commit c598922

Browse files
committed
code format
1 parent 82a0920 commit c598922

File tree

4 files changed

+80
-73
lines changed

4 files changed

+80
-73
lines changed

example/NetCam_LVI/main.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ void ImageCallback(const void *msg, size_t) {
1818
// 处理图像数据
1919
}
2020

21-
int main(int argc, char* argv[]) {
21+
int main(int argc, char *argv[]) {
2222
// 1.创建同步器
2323
Synchronizer synchronizer;
2424

@@ -35,8 +35,7 @@ int main(int argc, char* argv[]) {
3535
std::cout << "参数为 net,使用网口 192.168.1.188:8888" << std::endl;
3636
synchronizer.SetNetLink("192.168.1.188", 8888);
3737
} else {
38-
std::cerr << "未知参数: " << mode
39-
<< ",请使用 uart / net 或不传参数" << std::endl;
38+
std::cerr << "未知参数: " << mode << ",请使用 uart / net 或不传参数" << std::endl;
4039
return -1;
4140
}
4241
}

example/NetCam_LVI/main_ros.cpp

Lines changed: 28 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -6,23 +6,22 @@
66
#include <image_transport/image_transport.h>
77
#include <sensor_msgs/Imu.h>
88

9-
109
struct cam_config {
11-
bool onboard_imu = true;// 使用内部IMU
12-
bool extern_imu = false;// 使用外部IMU,TODO
13-
std::string imu_name = "onboard_imu";
14-
15-
// 相机名称 + 设备ID
16-
std::pair<std::string, int> CAM1 = {"cam_1", 1};
17-
std::pair<std::string, int> CAM2 = {"cam_2", -1};
18-
std::pair<std::string, int> CAM3 = {"cam_3", -1};
19-
std::pair<std::string, int> CAM4 = {"cam_4", -1}; // -1 代表没有
20-
21-
// 通信方式
22-
int type = 0; // 0 --> 串口通信 1 --> 网口通信
23-
std::string uart_dev = "/dev/ttyACM0";
24-
std::string net_ip = "192.168.1.188";
25-
int net_port = 8888;
10+
bool onboard_imu = true; // 使用内部IMU
11+
bool extern_imu = false; // 使用外部IMU,TODO
12+
std::string imu_name = "onboard_imu";
13+
14+
// 相机名称 + 设备ID
15+
std::pair<std::string, int> CAM1 = {"cam_1", 1};
16+
std::pair<std::string, int> CAM2 = {"cam_2", -1};
17+
std::pair<std::string, int> CAM3 = {"cam_3", -1};
18+
std::pair<std::string, int> CAM4 = {"cam_4", -1}; // -1 代表没有
19+
20+
// 通信方式
21+
int type = 0; // 0 --> 串口通信 1 --> 网口通信
22+
std::string uart_dev = "/dev/ttyACM0";
23+
std::string net_ip = "192.168.1.188";
24+
int net_port = 8888;
2625
};
2726
cam_config cfg;
2827

@@ -75,7 +74,7 @@ class CamDriver {
7574
} else if (cfg.type == 1) {
7675
synchronizer_.SetNetLink(cfg.net_ip, cfg.net_port);
7776
}
78-
77+
7978
mv_cam_ = std::make_shared<MvCam>();
8079
synchronizer_.UseSensor(mv_cam_);
8180

@@ -88,7 +87,6 @@ class CamDriver {
8887
if (cfg.CAM3.second >= 0) mv_cam_->SetParams({{cfg.CAM3.first, CAM_3}});
8988
if (cfg.CAM4.second >= 0) mv_cam_->SetParams({{cfg.CAM4.first, CAM_4}});
9089

91-
9290
if (cfg.CAM1.second >= 0) image_pubs_[cfg.CAM1.first] = it_.advertise(cfg.CAM1.first, 30);
9391
if (cfg.CAM2.second >= 0) image_pubs_[cfg.CAM2.first] = it_.advertise(cfg.CAM2.first, 30);
9492
if (cfg.CAM3.second >= 0) image_pubs_[cfg.CAM3.first] = it_.advertise(cfg.CAM3.first, 30);
@@ -102,10 +100,18 @@ class CamDriver {
102100
cfg.imu_name, std::bind(&CamDriver::ImuCallback, this, std::placeholders::_1, std::placeholders::_2));
103101
}
104102

105-
if (cfg.CAM1.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM1.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
106-
if (cfg.CAM2.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM2.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
107-
if (cfg.CAM3.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM3.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
108-
if (cfg.CAM4.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM4.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
103+
if (cfg.CAM1.second >= 0)
104+
Messenger::GetInstance().SubStruct(
105+
cfg.CAM1.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
106+
if (cfg.CAM2.second >= 0)
107+
Messenger::GetInstance().SubStruct(
108+
cfg.CAM2.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
109+
if (cfg.CAM3.second >= 0)
110+
Messenger::GetInstance().SubStruct(
111+
cfg.CAM3.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
112+
if (cfg.CAM4.second >= 0)
113+
Messenger::GetInstance().SubStruct(
114+
cfg.CAM4.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
109115
}
110116

111117
void Run() {

example/NetCam_LVI/main_ros2.cpp

Lines changed: 32 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -9,21 +9,21 @@
99
#include <sensor_msgs/msg/imu.hpp>
1010

1111
struct cam_config {
12-
bool onboard_imu = true;// 使用内部IMU
13-
bool extern_imu = false;// 使用外部IMU,TODO
14-
std::string imu_name = "onboard_imu";
15-
16-
// 相机名称 + 设备ID
17-
std::pair<std::string, int> CAM1 = {"cam_1", 1};
18-
std::pair<std::string, int> CAM2 = {"cam_2", -1};
19-
std::pair<std::string, int> CAM3 = {"cam_3", -1};
20-
std::pair<std::string, int> CAM4 = {"cam_4", -1}; // -1 代表没有
21-
22-
// 通信方式
23-
int type = 0; // 0 --> 串口通信 1 --> 网口通信
24-
std::string uart_dev = "/dev/ttyACM0";
25-
std::string net_ip = "192.168.1.188";
26-
int net_port = 8888;
12+
bool onboard_imu = true; // 使用内部IMU
13+
bool extern_imu = false; // 使用外部IMU,TODO
14+
std::string imu_name = "onboard_imu";
15+
16+
// 相机名称 + 设备ID
17+
std::pair<std::string, int> CAM1 = {"cam_1", 1};
18+
std::pair<std::string, int> CAM2 = {"cam_2", -1};
19+
std::pair<std::string, int> CAM3 = {"cam_3", -1};
20+
std::pair<std::string, int> CAM4 = {"cam_4", -1}; // -1 代表没有
21+
22+
// 通信方式
23+
int type = 0; // 0 --> 串口通信 1 --> 网口通信
24+
std::string uart_dev = "/dev/ttyACM0";
25+
std::string net_ip = "192.168.1.188";
26+
int net_port = 8888;
2727
};
2828
cam_config cfg;
2929

@@ -32,8 +32,9 @@ using namespace infinite_sense;
3232
class CamDriver final : public rclcpp::Node {
3333
public:
3434
CamDriver()
35-
: Node("ros2_cam_driver"), node_handle_(std::shared_ptr<CamDriver>(this, [](auto *) {})), transport_(node_handle_) {
36-
35+
: Node("ros2_cam_driver"),
36+
node_handle_(std::shared_ptr<CamDriver>(this, [](auto *) {})),
37+
transport_(node_handle_) {
3738
if (cfg.type == 0) {
3839
synchronizer_.SetUsbLink(cfg.uart_dev, 921600);
3940
} else if (cfg.type == 1) {
@@ -47,7 +48,6 @@ class CamDriver final : public rclcpp::Node {
4748
if (cfg.CAM3.second >= 0) mv_cam_->SetParams({{cfg.CAM3.first, CAM_3}});
4849
if (cfg.CAM4.second >= 0) mv_cam_->SetParams({{cfg.CAM4.first, CAM_4}});
4950

50-
5151
if (cfg.CAM1.second >= 0) image_pubs_[cfg.CAM1.first] = transport_.advertise(cfg.CAM1.first, 30);
5252
if (cfg.CAM2.second >= 0) image_pubs_[cfg.CAM2.first] = transport_.advertise(cfg.CAM2.first, 30);
5353
if (cfg.CAM3.second >= 0) image_pubs_[cfg.CAM3.first] = transport_.advertise(cfg.CAM3.first, 30);
@@ -65,14 +65,22 @@ class CamDriver final : public rclcpp::Node {
6565
{
6666
using namespace std::placeholders;
6767
if (cfg.onboard_imu) {
68-
Messenger::GetInstance().SubStruct(
69-
cfg.imu_name, std::bind(&CamDriver::ImuCallback, this, std::placeholders::_1, std::placeholders::_2));
68+
Messenger::GetInstance().SubStruct(
69+
cfg.imu_name, std::bind(&CamDriver::ImuCallback, this, std::placeholders::_1, std::placeholders::_2));
7070
}
7171

72-
if (cfg.CAM1.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM1.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
73-
if (cfg.CAM2.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM2.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
74-
if (cfg.CAM3.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM3.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
75-
if (cfg.CAM4.second >= 0) Messenger::GetInstance().SubStruct(cfg.CAM4.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
72+
if (cfg.CAM1.second >= 0)
73+
Messenger::GetInstance().SubStruct(
74+
cfg.CAM1.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
75+
if (cfg.CAM2.second >= 0)
76+
Messenger::GetInstance().SubStruct(
77+
cfg.CAM2.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
78+
if (cfg.CAM3.second >= 0)
79+
Messenger::GetInstance().SubStruct(
80+
cfg.CAM3.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
81+
if (cfg.CAM4.second >= 0)
82+
Messenger::GetInstance().SubStruct(
83+
cfg.CAM4.first, std::bind(&CamDriver::ImageCallback, this, std::placeholders::_1, std::placeholders::_2));
7684
}
7785
}
7886

@@ -104,7 +112,6 @@ class CamDriver final : public rclcpp::Node {
104112
image_pubs_[cam_data->name].publish(image_msg);
105113
}
106114

107-
108115
private:
109116
infinite_sense::Synchronizer synchronizer_;
110117
SharedPtr node_handle_;

example/NetCam_LVI/mv_cam.cpp

Lines changed: 18 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,11 @@
22
#include "infinite_sense.h"
33
#include "MvCameraControl.h"
44
#include <opencv2/opencv.hpp>
5-
#include <sys/mman.h> // mmap, PROT_READ, PROT_WRITE, MAP_SHARED 等
5+
#include <sys/mman.h> // mmap, PROT_READ, PROT_WRITE, MAP_SHARED 等
66
#include <sys/types.h>
77
#include <sys/stat.h>
8-
#include <fcntl.h> // open, O_RDWR, O_CREAT 等
9-
#include <unistd.h> // close, ftruncate
10-
8+
#include <fcntl.h> // open, O_RDWR, O_CREAT 等
9+
#include <unistd.h> // close, ftruncate
1110

1211
namespace infinite_sense {
1312

@@ -68,7 +67,6 @@ bool IsBayerGB8(const MvGvspPixelType type) {
6867
}
6968
}
7069

71-
7270
bool PrintDeviceInfo(const MV_CC_DEVICE_INFO *info) {
7371
if (info == nullptr) {
7472
LOG(WARNING) << "[WARNING] Failed to get camera details. Skipping...";
@@ -98,16 +96,14 @@ bool PrintDeviceInfo(const MV_CC_DEVICE_INFO *info) {
9896
MvCam::~MvCam() { Stop(); }
9997

10098
bool MvCam::Initialization() {
101-
10299
// TODO2: 获取共享内存文件指针,相机类初始化时调用
103-
const char *user_name = getlogin();
104-
std::string path_for_time_stamp = "/home/" + std::string(user_name) + "/timeshare";
105-
const char *shared_file_name = path_for_time_stamp.c_str();
100+
const char *user_name = getlogin();
101+
const std::string path_for_time_stamp = "/home/" + std::string(user_name) + "/timeshare";
102+
const char *shared_file_name = path_for_time_stamp.c_str();
106103

107-
int fd = open(shared_file_name, O_RDWR);
104+
const int fd = open(shared_file_name, O_RDWR);
108105

109-
pointt = (time_stamp *)mmap(NULL, sizeof(time_stamp), PROT_READ | PROT_WRITE,
110-
MAP_SHARED, fd, 0);
106+
pointt = static_cast<time_stamp *>(mmap(nullptr, sizeof(time_stamp), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0));
111107

112108
int n_ret = MV_OK;
113109
MV_CC_DEVICE_INFO_LIST st_device_list{};
@@ -236,14 +232,13 @@ void MvCam::Receive(void *handle, const std::string &name) {
236232
LOG(ERROR) << "Trigger cam: " << name << " not found!";
237233
}
238234
}
239-
235+
240236
// TODO3: 获取当前时间戳信息
241-
if(pointt != MAP_FAILED && pointt->low != 0)
242-
{
243-
// 赋值共享内存中的时间戳给相机帧
244-
cam_data.time_stamp_us = pointt->low;
237+
if (pointt != MAP_FAILED && pointt->low != 0) {
238+
// 赋值共享内存中的时间戳给相机帧
239+
cam_data.time_stamp_us = pointt->low;
245240
// LOG(INFO) << "time_stamp_s: " << cam_data.time_stamp_us/1000000 << " not found!";
246-
}
241+
}
247242

248243
MvGvspPixelType en_dst_pixel_type = PixelType_Gvsp_Undefined;
249244
unsigned int n_channel_num = 0;
@@ -256,17 +251,18 @@ void MvCam::Receive(void *handle, const std::string &name) {
256251
else if (IsMono(st_out_frame.stFrameInfo.enPixelType)) {
257252
n_channel_num = 1;
258253
en_dst_pixel_type = PixelType_Gvsp_Mono8;
259-
}
260-
else if (IsBayerGB8(st_out_frame.stFrameInfo.enPixelType)) {
254+
} else if (IsBayerGB8(st_out_frame.stFrameInfo.enPixelType)) {
261255
n_channel_num = 1;
262256
en_dst_pixel_type = PixelType_Gvsp_BayerGB8;
263257
}
264258
if (n_channel_num != 0) {
265259
cam_data.name = name;
266260
if (en_dst_pixel_type == PixelType_Gvsp_BayerGB8) {
267-
cv::Mat cv_image = cv::Mat(st_out_frame.stFrameInfo.nHeight, st_out_frame.stFrameInfo.nWidth,CV_8UC1, st_out_frame.pBufAddr);
261+
auto cv_image = cv::Mat(st_out_frame.stFrameInfo.nHeight, st_out_frame.stFrameInfo.nWidth, CV_8UC1,
262+
st_out_frame.pBufAddr);
268263
cv::cvtColor(cv_image, out_image, cv::COLOR_BayerBG2GRAY);
269-
cam_data.image = GMat(st_out_frame.stFrameInfo.nHeight, st_out_frame.stFrameInfo.nWidth,CV_8UC1, out_image.data);
264+
cam_data.image =
265+
GMat(st_out_frame.stFrameInfo.nHeight, st_out_frame.stFrameInfo.nWidth, CV_8UC1, out_image.data);
270266
}
271267
if (en_dst_pixel_type == PixelType_Gvsp_Mono8) {
272268
cam_data.image = GMat(st_out_frame.stFrameInfo.nHeight, st_out_frame.stFrameInfo.nWidth,
@@ -322,4 +318,3 @@ void MvCam::Start() {
322318
}
323319
}
324320
} // namespace infinite_sense
325-

0 commit comments

Comments
 (0)