Skip to content
This repository was archived by the owner on Jun 11, 2025. It is now read-only.

Commit ae435c9

Browse files
committed
1. format code; 2. add some commit
1 parent bb34f30 commit ae435c9

2 files changed

Lines changed: 59 additions & 57 deletions

File tree

demo/uart_demo/main_ros.cpp

Lines changed: 58 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -8,80 +8,81 @@
88
#include "data_manager.h"
99

1010
inline ros::Time CreateRosTimestamp(const uint64_t timestamp_micoseconds) {
11-
static constexpr uint32_t kNanosecondsPerSecond = 1e9;
12-
const auto kTimestampU64 = timestamp_micoseconds * 1000;
13-
const uint32_t kTimestampSec = kTimestampU64 / kNanosecondsPerSecond;
14-
const uint32_t kRosTimestampNsec = kTimestampU64 - (kTimestampSec * kNanosecondsPerSecond);
15-
return {kTimestampSec, kRosTimestampNsec};
11+
static constexpr uint32_t kNanosecondsPerSecond = 1e9;
12+
const auto kTimestampU64 = timestamp_micoseconds * 1000;
13+
const uint32_t kTimestampSec = kTimestampU64 / kNanosecondsPerSecond;
14+
const uint32_t kRosTimestampNsec = kTimestampU64 - (kTimestampSec * kNanosecondsPerSecond);
15+
return {kTimestampSec, kRosTimestampNsec};
1616
}
1717

1818
void PublishIMUData(const ros::Publisher& pub, const ImuData& imudata) {
19-
sensor_msgs::Imu imu_msg_data;
20-
imu_msg_data.header.frame_id = "/base_imu_link";
21-
imu_msg_data.header.stamp = CreateRosTimestamp(imudata.time_stamp_us);
19+
sensor_msgs::Imu imu_msg_data;
20+
imu_msg_data.header.frame_id = "/base_imu_link";
21+
imu_msg_data.header.stamp = CreateRosTimestamp(imudata.time_stamp_us);
2222

23-
imu_msg_data.angular_velocity.x = imudata.gx;
24-
imu_msg_data.angular_velocity.y = imudata.gy;
25-
imu_msg_data.angular_velocity.z = imudata.gz;
23+
imu_msg_data.angular_velocity.x = imudata.gx;
24+
imu_msg_data.angular_velocity.y = imudata.gy;
25+
imu_msg_data.angular_velocity.z = imudata.gz;
2626

27-
imu_msg_data.linear_acceleration.x = imudata.ax;
28-
imu_msg_data.linear_acceleration.y = imudata.ay;
29-
imu_msg_data.linear_acceleration.z = imudata.az;
27+
imu_msg_data.linear_acceleration.x = imudata.ax;
28+
imu_msg_data.linear_acceleration.y = imudata.ay;
29+
imu_msg_data.linear_acceleration.z = imudata.az;
3030

31-
pub.publish(imu_msg_data);
31+
pub.publish(imu_msg_data);
3232
}
3333
void SigIntHandler(int sig) {
3434
ros::shutdown(); // 让ROS节点安全退出
3535
}
3636
int main(int argc, char** argv) {
37-
// Wait 5 seconds for the camera to start up.
38-
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
39-
// ROS 初始化
40-
ros::init(argc, argv, "CIS",ros::init_options::NoSigintHandler);
41-
ros::NodeHandle node;
42-
// 串口线程初始化
43-
auto serial_manager =std::make_shared<SerialManager>("/dev/ttyACM0");
44-
serial_manager->Start();
37+
// Wait 5 seconds for the camera to start up.
38+
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
39+
// ROS 初始化
40+
ros::init(argc, argv, "CIS", ros::init_options::NoSigintHandler);
41+
ros::NodeHandle node;
42+
// 串口线程初始化
43+
auto serial_manager = std::make_shared<SerialManager>("/dev/ttyACM0");
44+
serial_manager->Start();
4545

46-
// IMU数据发布
47-
ros::Publisher imu_pub = node.advertise<sensor_msgs::Imu>("/imu_sync_board", 1000);
46+
// IMU数据发布
47+
ros::Publisher imu_pub = node.advertise<sensor_msgs::Imu>("/imu_sync_board", 1000);
4848

49-
// 相机线程初始化
50-
CamManger::GetInstance().Initialization();
51-
CamManger::GetInstance().Start();
49+
// 相机线程初始化
50+
CamManger::GetInstance().Initialization();
51+
CamManger::GetInstance().Start();
5252

53-
// 等待相机启动
54-
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
53+
// 等待相机启动
54+
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
5555

56-
// 遍历所有相机,新建发布者
57-
image_transport::ImageTransport it(node);
58-
std::vector<std::string> all_cam_names;
59-
DataManger::GetInstance().GetAllCamNames(all_cam_names);
60-
std::cout << "Number of cameras detected " << all_cam_names.size() << std::endl;
61-
std::map<std::string, image_transport::Publisher> pub_list;
62-
for (auto& cam : all_cam_names) {
63-
pub_list[cam] = it.advertise(cam, 30);
64-
}
56+
// 遍历所有相机,新建发布者
57+
image_transport::ImageTransport it(node);
58+
std::vector<std::string> all_cam_names;
59+
DataManger::GetInstance().GetAllCamNames(all_cam_names);
60+
std::cout << "Number of cameras detected " << all_cam_names.size() << std::endl;
61+
std::map<std::string, image_transport::Publisher> pub_list;
62+
for (auto& cam : all_cam_names) {
63+
pub_list[cam] = it.advertise(cam, 30);
64+
}
6565

66-
// ROS循环发布传感器数据
67-
ros::Rate loop_rate(1000);
68-
ImuData imudata{};
66+
// ROS循环发布传感器数据
67+
ros::Rate loop_rate(1000);
68+
ImuData imudata{};
6969

70-
while (node.ok()) {
71-
// 获取IMU数据
72-
while (DataManger::GetInstance().GetNewImuData(imudata)) {
73-
// 发布IMU数据
74-
PublishIMUData(imu_pub, imudata);
75-
}
76-
// 遍历所有相机,发布图像数据
77-
ImgData img_data{};
78-
for (auto& cam : all_cam_names) {
79-
// 获取图像数据
80-
while (DataManger::GetInstance().GetNewCamData(cam, img_data)) {
81-
// 发布图像数据
82-
sensor_msgs::ImagePtr msg =
83-
cv_bridge::CvImage(std_msgs::Header(), "mono8", img_data.image.clone()).toImageMsg();
84-
msg->header.stamp = CreateRosTimestamp(img_data.time_stamp_us);
70+
while (node.ok()) {
71+
// 获取IMU数据
72+
while (DataManger::GetInstance().GetNewImuData(imudata)) {
73+
// 发布IMU数据
74+
PublishIMUData(imu_pub, imudata);
75+
}
76+
// 遍历所有相机,发布图像数据
77+
ImgData img_data{};
78+
for (auto& cam : all_cam_names) {
79+
// 获取图像数据
80+
while (DataManger::GetInstance().GetNewCamData(cam, img_data)) {
81+
// 发布图像数据
82+
sensor_msgs::ImagePtr msg =
83+
// mono8:灰度类型,bgr8:彩图,具体需要根据相机类型进行修改
84+
cv_bridge::CvImage(std_msgs::Header(), "mono8", img_data.image.clone()).toImageMsg();
85+
msg->header.stamp = CreateRosTimestamp(img_data.time_stamp_us);
8586
pub_list[cam].publish(msg);
8687
}
8788
}

demo/udp_demo/main_ros.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,7 @@ int main(int argc, char** argv) {
8383
for (auto& cam : all_cam_names) {
8484
while (DataManger::GetInstance().GetNewCamData(cam, img_data)) {
8585
sensor_msgs::ImagePtr msg =
86+
// mono8:灰度类型,bgr8:彩图,具体需要根据相机类型进行修改
8687
cv_bridge::CvImage(std_msgs::Header(), "mono8", img_data.image.clone()).toImageMsg();
8788
msg->header.stamp = CreateRosTimestamp(img_data.time_stamp_us);
8889
pub_list[cam].publish(msg);

0 commit comments

Comments
 (0)