Skip to content

Commit f27d664

Browse files
committed
add 'scale_factors' field
1 parent c60f9e4 commit f27d664

File tree

2 files changed

+32
-11
lines changed

2 files changed

+32
-11
lines changed

exe/tool/raw_inertial_to_bag.cpp

+18-8
Original file line numberDiff line numberDiff line change
@@ -76,14 +76,24 @@ int main(int argc, char **argv) {
7676
parPath.string());
7777
}
7878

79-
auto stampToSedScale =
80-
ns_ikalibr::GetParamFromROS<double>("/ikalibr_raw_inertial_to_bag/stamp_to_sed_scale");
79+
auto scaleFactorsStr =
80+
ns_ikalibr::GetParamFromROS<std::string>("/ikalibr_raw_inertial_to_bag/scale_factors");
81+
auto scaleFactorsVec = ns_ikalibr::SplitString(scaleFactorsStr, ';');
82+
if (scaleFactorsVec.size() != 3) {
83+
throw ns_ikalibr::Status(ns_ikalibr::Status::ERROR,
84+
"the element count in 'scale_factors' should be three!!!");
85+
}
86+
double stampToSedScale = std::stod(scaleFactorsVec.at(0));
8187
spdlog::info("raw stamp to second-unit timestamp scale: '{}'", stampToSedScale);
8288
if (stampToSedScale <= 0.0) {
8389
throw ns_ikalibr::Status(
8490
ns_ikalibr::Status::ERROR,
8591
"raw stamp to second-unit timestamp scale should be positive!!! '{}'");
8692
}
93+
double gyroScale = std::stod(scaleFactorsVec.at(1));
94+
spdlog::info("gyroscope measurements scale: '{}'", gyroScale);
95+
double acceScale = std::stod(scaleFactorsVec.at(2));
96+
spdlog::info("accelerator measurements scale: '{}'", acceScale);
8797

8898
auto headLineCount =
8999
ns_ikalibr::GetParamFromROS<int>("/ikalibr_raw_inertial_to_bag/head_line_count");
@@ -148,12 +158,12 @@ int main(int argc, char **argv) {
148158
}
149159
sensor_msgs::Imu imu;
150160
imu.header.stamp = ros::Time(std::stod(elems.at(index.at(TIME))) * stampToSedScale);
151-
imu.linear_acceleration.x = std::stod(elems.at(index.at(AX)));
152-
imu.linear_acceleration.y = std::stod(elems.at(index.at(AY)));
153-
imu.linear_acceleration.z = std::stod(elems.at(index.at(AZ)));
154-
imu.angular_velocity.x = std::stod(elems.at(index.at(GX)));
155-
imu.angular_velocity.y = std::stod(elems.at(index.at(GY)));
156-
imu.angular_velocity.z = std::stod(elems.at(index.at(GZ)));
161+
imu.linear_acceleration.x = std::stod(elems.at(index.at(AX))) * acceScale;
162+
imu.linear_acceleration.y = std::stod(elems.at(index.at(AY))) * acceScale;
163+
imu.linear_acceleration.z = std::stod(elems.at(index.at(AZ))) * acceScale;
164+
imu.angular_velocity.x = std::stod(elems.at(index.at(GX))) * gyroScale;
165+
imu.angular_velocity.y = std::stod(elems.at(index.at(GY))) * gyroScale;
166+
imu.angular_velocity.z = std::stod(elems.at(index.at(GZ))) * gyroScale;
157167
// std::cout << imu.header.stamp << std::endl;
158168
// std::cout << imu.linear_acceleration << std::endl;
159169
// std::cout << imu.angular_velocity << std::endl;

launch/tool/ikalibr-raw-inertial-to-bag.launch

+14-3
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,24 @@
33

44
<node pkg="ikalibr" type="ikalibr_raw_inertial_to_bag" name="ikalibr_raw_inertial_to_bag" output="screen">
55
<!-- raw inertial path -->
6-
<param name="raw_inertial_path" value="/home/csl/dataset/tum/rolling-shutter/dataset-seq10/dso/imu.txt" type="string"/>
6+
<param name="raw_inertial_path" value="/home/csl/dataset/tum/rolling-shutter/dataset-seq10/dso/imu.txt"
7+
type="string"/>
78
<!-- image topic (what message topic for images in the generated rosbag you want) -->
89
<param name="imu_topic" value="/imu/frame" type="string"/>
910
<!-- output bag path -->
1011
<param name="bag_path" value="/home/csl/dataset/tum/rolling-shutter/dataset-seq10/imu.bag" type="string"/>
11-
<!-- timestamp (second) = stamp * ${stamp_to_sed_scale} -->
12-
<param name="stamp_to_sed_scale" value="1E-9" type="double"/>
12+
<!--
13+
scale_factors = {scale_factor_on_timestamp;scale_factor_on_gyro_mes;scale_factor_on_acce_mes},
14+
split by a semicolon. For example:
15+
(1) If your time unit is nanoseconds, you need to use {1E-9} to convert it to single seconds. Converting time
16+
units to seconds is necessary when making ros bags.
17+
(2) If your angular velocity is in deg/s, if you want to convert it to rad/s, you need to use {0.01745329} to
18+
convert. This is not necessary, if you want to keep the original unit, just fill in {1.0}.
19+
(3) If your acceleration is in G, if you want to convert it to m/s^2, you need to convert it by the
20+
local gravity (about 9.8 m/s^2). This is not necessary, if you want to keep the original units,
21+
just fill in {1.0}.
22+
-->
23+
<param name="scale_factors" value="1E-9;1.0;1.0" type="double"/>
1324
<!-- how many lines to jump at head (invalid lines, which are only notes) -->
1425
<param name="head_line_count" value="1" type="int"/>
1526
<!-- the split character (only one character), pass it in the middle of the big parentheses -->

0 commit comments

Comments
 (0)