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

Commit 9dbd031

Browse files
committed
update: 1.commit update;2. delete some ReadMe.md;
1 parent b766507 commit 9dbd031

6 files changed

Lines changed: 22 additions & 24 deletions

File tree

demo/customised_camera/ReadMe.md

Whitespace-only changes.

demo/customised_camera/main_ros.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -6,12 +6,12 @@
66
#include "customised_camera.h"
77
#include "data_manager.h"
88

9-
inline ros::Time CreateRosTimestamp(const uint64_t timestamp_micoseconds) {
10-
static constexpr uint32_t kNanosecondsPerSecond = 1e9;
11-
const auto kTimestampU64 = timestamp_micoseconds * 1000;
12-
const uint32_t kTimestampSec = kTimestampU64 / kNanosecondsPerSecond;
13-
const uint32_t kRosTimestampNsec = kTimestampU64 - (kTimestampSec * kNanosecondsPerSecond);
14-
return {kTimestampSec, kRosTimestampNsec};
9+
inline ros::Time CreateRosTimestamp(const uint64_t mico_sec) {
10+
uint32_t nsec_per_second = 1e9;
11+
auto u64 = mico_sec * 1000;
12+
uint32_t sec = u64 / nsec_per_second;
13+
uint32_t nsec = u64 - (sec * nsec_per_second);
14+
return {sec, nsec};
1515
}
1616

1717
void PublishIMUData(const ros::Publisher& pub, const ImuData& imudata) {
@@ -34,7 +34,7 @@ int main(int argc, char** argv) {
3434
// 等待5秒
3535
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
3636
// ROS 初始化
37-
ros::init(argc, argv, "CIS",ros::init_options::NoSigintHandler);
37+
ros::init(argc, argv, "CustomisedCamera",ros::init_options::NoSigintHandler);
3838
ros::NodeHandle node;
3939

4040
// IMU数据发布

demo/uart_demo/main_ros.cpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,12 @@
77
#include "serial_manager.h"
88
#include "data_manager.h"
99

10-
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};
10+
inline ros::Time CreateRosTimestamp(const uint64_t mico_sec) {
11+
uint32_t nsec_per_second = 1e9;
12+
auto u64 = mico_sec * 1000;
13+
uint32_t sec = u64 / nsec_per_second;
14+
uint32_t nsec = u64 - (sec * nsec_per_second);
15+
return {sec, nsec};
1616
}
1717

1818
void PublishIMUData(const ros::Publisher& pub, const ImuData& imudata) {
@@ -34,10 +34,9 @@ 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.
3837
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
3938
// ROS 初始化
40-
ros::init(argc, argv, "CIS", ros::init_options::NoSigintHandler);
39+
ros::init(argc, argv, "uart_demo", ros::init_options::NoSigintHandler);
4140
ros::NodeHandle node;
4241
// 串口线程初始化
4342
auto serial_manager = std::make_shared<SerialManager>("/dev/ttyACM0");

demo/udp_demo/ReadMe.md

Whitespace-only changes.

demo/udp_demo/main_ros.cpp

Lines changed: 8 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -9,20 +9,19 @@
99
#include "Fusion.h"
1010

1111
FusionAhrs ahrs;
12-
13-
inline ros::Time CreateRosTimestamp(const uint64_t timestamp_micoseconds) {
14-
static constexpr uint32_t kNanosecondsPerSecond = 1e9;
15-
const auto kTimestampU64 = timestamp_micoseconds * 1000;
16-
const uint32_t kTimestampSec = kTimestampU64 / kNanosecondsPerSecond;
17-
const uint32_t kRosTimestampNsec = kTimestampU64 - (kTimestampSec * kNanosecondsPerSecond);
18-
return {kTimestampSec, kRosTimestampNsec};
12+
inline ros::Time CreateRosTimestamp(const uint64_t mico_sec) {
13+
uint32_t nsec_per_second = 1e9;
14+
auto u64 = mico_sec * 1000;
15+
uint32_t sec = u64 / nsec_per_second;
16+
uint32_t nsec = u64 - (sec * nsec_per_second);
17+
return {sec, nsec};
1918
}
2019

2120
void PublishIMUData(const ros::Publisher& pub, const ImuData& imudata) {
2221

2322
FusionVector gyroscope = {imudata.gx, imudata.gy, imudata.gz};
2423
FusionVector accelerometer = {imudata.ax, imudata.ay, imudata.az};
25-
FusionAhrsUpdateNoMagnetometer(&ahrs, gyroscope, accelerometer, 0.0025f);
24+
FusionAhrsUpdateNoMagnetometer(&ahrs, gyroscope, accelerometer, 0.005f);
2625
FusionQuaternion q = FusionAhrsGetQuaternion(&ahrs);
2726

2827
sensor_msgs::Imu imu_msg_data;
@@ -48,7 +47,7 @@ void SigIntHandler(int sig) {
4847
ros::shutdown(); // 让ROS节点安全退出
4948
}
5049
int main(int argc, char** argv) {
51-
ros::init(argc, argv, "CIS",ros::init_options::NoSigintHandler);
50+
ros::init(argc, argv, "udp_demo",ros::init_options::NoSigintHandler);
5251
ros::NodeHandle node;
5352
FusionAhrsInitialise(&ahrs);
5453
std::this_thread::sleep_for(std::chrono::milliseconds(5000));

demo/zmq_demo/ReadMe.md

Whitespace-only changes.

0 commit comments

Comments
 (0)