@@ -76,14 +76,24 @@ int main(int argc, char **argv) {
76
76
parPath.string ());
77
77
}
78
78
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 ));
81
87
spdlog::info (" raw stamp to second-unit timestamp scale: '{}'" , stampToSedScale);
82
88
if (stampToSedScale <= 0.0 ) {
83
89
throw ns_ikalibr::Status (
84
90
ns_ikalibr::Status::ERROR,
85
91
" raw stamp to second-unit timestamp scale should be positive!!! '{}'" );
86
92
}
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);
87
97
88
98
auto headLineCount =
89
99
ns_ikalibr::GetParamFromROS<int >(" /ikalibr_raw_inertial_to_bag/head_line_count" );
@@ -148,12 +158,12 @@ int main(int argc, char **argv) {
148
158
}
149
159
sensor_msgs::Imu imu;
150
160
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 ;
157
167
// std::cout << imu.header.stamp << std::endl;
158
168
// std::cout << imu.linear_acceleration << std::endl;
159
169
// std::cout << imu.angular_velocity << std::endl;
0 commit comments