test_dynamic_init.cpp
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #include <cmath>
23 #include <csignal>
24 #include <deque>
25 #include <iomanip>
26 #include <sstream>
27 #include <unistd.h>
28 #include <vector>
29 
30 #include <boost/date_time/posix_time/posix_time.hpp>
31 #include <boost/filesystem.hpp>
32 
33 #if ROS_AVAILABLE == 1
34 #include <nav_msgs/Path.h>
35 #include <ros/ros.h>
36 #include <sensor_msgs/PointCloud.h>
37 #include <sensor_msgs/PointCloud2.h>
39 #endif
40 
43 #include "sim/SimulatorInit.h"
44 
45 #include "track/TrackSIM.h"
46 #include "types/IMU.h"
47 #include "types/Landmark.h"
48 #include "types/PoseJPL.h"
49 #include "utils/colors.h"
50 #include "utils/sensor_data.h"
51 
52 using namespace ov_init;
53 
54 // Define the function to be called when ctrl-c (SIGINT) is sent to process
55 void signal_callback_handler(int signum) { std::exit(signum); }
56 
57 // taken from ov_eval/src/alignment/AlignUtils.h
58 static inline double get_best_yaw(const Eigen::Matrix<double, 3, 3> &C) {
59  double A = C(0, 1) - C(1, 0);
60  double B = C(0, 0) + C(1, 1);
61  // return M_PI_2 - atan2(B, A);
62  return atan2(A, B);
63 }
64 // taken from ov_eval/src/alignment/AlignUtils.h
65 void align_posyaw_single(const Eigen::Vector4d &q_es_0, const Eigen::Vector3d &p_es_0, const Eigen::Vector4d &q_gt_0,
66  const Eigen::Vector3d &p_gt_0, Eigen::Matrix3d &R, Eigen::Vector3d &t) {
67  Eigen::Matrix3d g_rot = ov_core::quat_2_Rot(q_gt_0).transpose();
68  Eigen::Matrix3d est_rot = ov_core::quat_2_Rot(q_es_0).transpose();
69  Eigen::Matrix3d C_R = est_rot * g_rot.transpose();
70  double theta = get_best_yaw(C_R);
71  R = ov_core::rot_z(theta);
72  t.noalias() = p_gt_0 - R * p_es_0;
73 }
74 
75 // Main function
76 int main(int argc, char **argv) {
77 
78  // Ensure we have a path, if the user passes it then we should use it
79  std::string config_path = "unset_path_to_config.yaml";
80  if (argc > 1) {
81  config_path = argv[1];
82  }
83 
84 #if ROS_AVAILABLE == 1
85  // Launch our ros node
86  ros::init(argc, argv, "test_dynamic_init");
87  auto nh = std::make_shared<ros::NodeHandle>("~");
88  nh->param<std::string>("config_path", config_path, config_path);
89 
90  // Topics to publish
91  auto pub_pathimu = nh->advertise<nav_msgs::Path>("/ov_msckf/pathimu", 2);
92  PRINT_DEBUG("Publishing: %s\n", pub_pathimu.getTopic().c_str());
93  auto pub_pathgt = nh->advertise<nav_msgs::Path>("/ov_msckf/pathgt", 2);
94  PRINT_DEBUG("Publishing: %s\n", pub_pathgt.getTopic().c_str());
95  auto pub_loop_point = nh->advertise<sensor_msgs::PointCloud>("/ov_msckf/loop_feats", 2);
96  PRINT_DEBUG("Publishing: %s\n", pub_loop_point.getTopic().c_str());
97  auto pub_points_sim = nh->advertise<sensor_msgs::PointCloud2>("/ov_msckf/points_sim", 2);
98  PRINT_DEBUG("Publishing: %s\n", pub_points_sim.getTopic().c_str());
99 #endif
100 
101  // Load the config
102  auto parser = std::make_shared<ov_core::YamlParser>(config_path);
103 #if ROS_AVAILABLE == 1
104  parser->set_node_handler(nh);
105 #endif
106 
107  // Verbosity
108  std::string verbosity = "INFO";
109  parser->parse_config("verbosity", verbosity);
111 
112  // Create the simulator
114  params.print_and_load(parser);
115  params.print_and_load_simulation(parser);
116  if (!parser->successful()) {
117  PRINT_ERROR(RED "unable to parse all parameters, please fix\n" RESET);
118  std::exit(EXIT_FAILURE);
119  }
120  SimulatorInit sim(params);
121 
122  // Our initialization class objects
123  auto imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
124  auto tracker = std::make_shared<ov_core::TrackSIM>(params.camera_intrinsics, 0);
125  auto initializer = std::make_shared<DynamicInitializer>(params, tracker->get_feature_database(), imu_readings);
126 
127  //===================================================================================
128  //===================================================================================
129  //===================================================================================
130 
131  // Buffer our camera image
132  double buffer_timecam = -1;
133  std::vector<int> buffer_camids;
134  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
135 
136  // Continue to simulate until we have processed all the measurements
137  signal(SIGINT, signal_callback_handler);
138  while (sim.ok()) {
139 
140  // IMU: get the next simulated IMU measurement if we have it
141  ov_core::ImuData message_imu;
142  bool hasimu = sim.get_next_imu(message_imu.timestamp, message_imu.wm, message_imu.am);
143  if (hasimu) {
144  imu_readings->push_back(message_imu);
145  }
146 
147  // CAM: get the next simulated camera uv measurements if we have them
148  double time_cam;
149  std::vector<int> camids;
150  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
151  bool hascam = sim.get_next_cam(time_cam, camids, feats);
152  if (hascam) {
153 
154  // Pass to our feature database / tracker
155  if (buffer_timecam != -1) {
156 
157  // Feed it
158  tracker->feed_measurement_simulation(buffer_timecam, buffer_camids, buffer_feats);
159 
160  // Display the resulting tracks
161  // cv::Mat img_history;
162  // tracker->display_history(img_history, 255, 255, 0, 255, 255, 255);
163  // cv::imshow("Track History", img_history);
164  // cv::waitKey(1);
165  }
166  buffer_timecam = time_cam;
167  buffer_camids = camids;
168  buffer_feats = feats;
169 
170  // Return states of our initializer
171  double timestamp = -1;
172  Eigen::MatrixXd covariance;
173  std::vector<std::shared_ptr<ov_type::Type>> order;
174  std::shared_ptr<ov_type::IMU> _imu;
175  std::map<double, std::shared_ptr<ov_type::PoseJPL>> _clones_IMU;
176  std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark>> _features_SLAM;
177 
178  // First we will try to make sure we have all the data required for our initialization
179  boost::posix_time::ptime rT1 = boost::posix_time::microsec_clock::local_time();
180  bool success = initializer->initialize(timestamp, covariance, order, _imu, _clones_IMU, _features_SLAM);
181  boost::posix_time::ptime rT2 = boost::posix_time::microsec_clock::local_time();
182  double time = (rT2 - rT1).total_microseconds() * 1e-6;
183  if (success) {
184 
185  // Debug that we finished!
186  PRINT_INFO(GREEN "success! got initialized state information (%.4f seconds)\n" RESET, time);
187 
188  // First lets align the groundtruth state with the IMU state
189  // NOTE: imu biases do not have to be corrected with the pos yaw alignment here...
190  Eigen::Matrix<double, 17, 1> gt_imu;
191  bool success1 = sim.get_state(timestamp + sim.get_true_parameters().calib_camimu_dt, gt_imu);
192  assert(success1);
193  Eigen::Matrix3d R_ESTtoGT_imu;
194  Eigen::Vector3d t_ESTinGT_imu;
195  align_posyaw_single(_imu->quat(), _imu->pos(), gt_imu.block(1, 0, 4, 1), gt_imu.block(5, 0, 3, 1), R_ESTtoGT_imu, t_ESTinGT_imu);
196  gt_imu.block(1, 0, 4, 1) = ov_core::quat_multiply(gt_imu.block(1, 0, 4, 1), ov_core::rot_2_quat(R_ESTtoGT_imu));
197  gt_imu.block(5, 0, 3, 1) = R_ESTtoGT_imu.transpose() * (gt_imu.block(5, 0, 3, 1) - t_ESTinGT_imu);
198  gt_imu.block(8, 0, 3, 1) = R_ESTtoGT_imu.transpose() * gt_imu.block(8, 0, 3, 1);
199 
200  // Finally compute the error
201  Eigen::Matrix<double, 15, 1> err = Eigen::Matrix<double, 15, 1>::Zero();
202  Eigen::Matrix3d R_GtoI_gt = ov_core::quat_2_Rot(gt_imu.block(1, 0, 4, 1));
203  Eigen::Matrix3d R_GtoI_hat = _imu->Rot();
204  err.block(0, 0, 3, 1) = -ov_core::log_so3(R_GtoI_gt * R_GtoI_hat.transpose());
205  err.block(3, 0, 3, 1) = gt_imu.block(5, 0, 3, 1) - _imu->pos();
206  err.block(6, 0, 3, 1) = gt_imu.block(8, 0, 3, 1) - _imu->vel();
207  err.block(9, 0, 3, 1) = gt_imu.block(11, 0, 3, 1) - _imu->bias_g();
208  err.block(12, 0, 3, 1) = gt_imu.block(14, 0, 3, 1) - _imu->bias_a();
209 
210  // debug print the error of the recovered IMU state
211  PRINT_INFO(REDPURPLE "e_ori = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f,%.3f (est)\n" RESET,
212  180.0 / M_PI * err(0 + 0), 180.0 / M_PI * err(0 + 1), 180.0 / M_PI * err(0 + 2), gt_imu(1), gt_imu(2), gt_imu(3),
213  gt_imu(4), _imu->quat()(0), _imu->quat()(1), _imu->quat()(2), _imu->quat()(3));
214  PRINT_INFO(REDPURPLE "e_pos = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(3 + 0), err(3 + 1),
215  err(3 + 2), gt_imu(5), gt_imu(6), gt_imu(7), _imu->pos()(0), _imu->pos()(1), _imu->pos()(2));
216  PRINT_INFO(REDPURPLE "e_vel = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(6 + 0), err(6 + 1),
217  err(6 + 2), gt_imu(8), gt_imu(9), gt_imu(10), _imu->vel()(0), _imu->vel()(1), _imu->vel()(2));
218  PRINT_INFO(REDPURPLE "e_bias_g = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(9 + 0), err(9 + 1),
219  err(9 + 2), gt_imu(11), gt_imu(12), gt_imu(13), _imu->bias_g()(0), _imu->bias_g()(1), _imu->bias_g()(2));
220  PRINT_INFO(REDPURPLE "e_bias_a = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(12 + 0), err(12 + 1),
221  err(12 + 2), gt_imu(14), gt_imu(15), gt_imu(16), _imu->bias_a()(0), _imu->bias_a()(1), _imu->bias_a()(2));
222 
223  // calculate normalized estimation error squared
224  // the recovered error should be on the order of the state size (15 or 3 for marginals)
225  Eigen::MatrixXd information = covariance.inverse();
226  double nees_total = (err.transpose() * information * err)(0, 0);
227  double nees_ori = (err.block(0, 0, 3, 1).transpose() * information.block(0, 0, 3, 3) * err.block(0, 0, 3, 1))(0, 0);
228  double nees_pos = (err.block(3, 0, 3, 1).transpose() * information.block(3, 3, 3, 3) * err.block(3, 0, 3, 1))(0, 0);
229  double nees_vel = (err.block(6, 0, 3, 1).transpose() * information.block(6, 6, 3, 3) * err.block(6, 0, 3, 1))(0, 0);
230  double nees_bg = (err.block(9, 0, 3, 1).transpose() * information.block(9, 9, 3, 3) * err.block(9, 0, 3, 1))(0, 0);
231  double nees_ba = (err.block(12, 0, 3, 1).transpose() * information.block(12, 12, 3, 3) * err.block(12, 0, 3, 1))(0, 0);
232  PRINT_INFO(REDPURPLE "nees total = %.3f | ori = %.3f | pos = %.3f (ideal is 15 and 3)\n" RESET, nees_total, nees_ori, nees_pos);
233  PRINT_INFO(REDPURPLE "nees vel = %.3f | bg = %.3f | ba = %.3f (ideal 3)\n" RESET, nees_vel, nees_bg, nees_ba);
234 
235 #if ROS_AVAILABLE == 1
236  // Align the groundtruth to the current estimate yaw
237  // Only use the first frame so we can see the drift
238  double oldestpose_time = -1;
239  std::shared_ptr<ov_type::PoseJPL> oldestpose = nullptr;
240  for (auto const &_pose : _clones_IMU) {
241  if (oldestpose == nullptr || _pose.first < oldestpose_time) {
242  oldestpose_time = _pose.first;
243  oldestpose = _pose.second;
244  }
245  }
246  assert(oldestpose != nullptr);
247  Eigen::Vector4d q_es_0, q_gt_0;
248  Eigen::Vector3d p_es_0, p_gt_0;
249  q_es_0 = oldestpose->quat();
250  p_es_0 = oldestpose->pos();
251  Eigen::Matrix<double, 17, 1> gt_imustate_0;
252  bool success2 = sim.get_state(oldestpose_time + sim.get_true_parameters().calib_camimu_dt, gt_imustate_0);
253  assert(success2);
254  q_gt_0 = gt_imustate_0.block(1, 0, 4, 1);
255  p_gt_0 = gt_imustate_0.block(5, 0, 3, 1);
256  Eigen::Matrix3d R_ESTtoGT;
257  Eigen::Vector3d t_ESTinGT;
258  align_posyaw_single(q_es_0, p_es_0, q_gt_0, p_gt_0, R_ESTtoGT, t_ESTinGT);
259 
260  // Pose states
261  nav_msgs::Path arrEST, arrGT;
262  arrEST.header.stamp = ros::Time::now();
263  arrEST.header.frame_id = "global";
264  arrGT.header.stamp = ros::Time::now();
265  arrGT.header.frame_id = "global";
266  for (auto const &_pose : _clones_IMU) {
267  geometry_msgs::PoseStamped poseEST, poseGT;
268  poseEST.header.stamp = ros::Time(_pose.first);
269  poseEST.header.frame_id = "global";
270  poseEST.pose.orientation.x = _pose.second->quat()(0, 0);
271  poseEST.pose.orientation.y = _pose.second->quat()(1, 0);
272  poseEST.pose.orientation.z = _pose.second->quat()(2, 0);
273  poseEST.pose.orientation.w = _pose.second->quat()(3, 0);
274  poseEST.pose.position.x = _pose.second->pos()(0, 0);
275  poseEST.pose.position.y = _pose.second->pos()(1, 0);
276  poseEST.pose.position.z = _pose.second->pos()(2, 0);
277  Eigen::Matrix<double, 17, 1> gt_imustate;
278  bool success3 = sim.get_state(_pose.first + sim.get_true_parameters().calib_camimu_dt, gt_imustate);
279  assert(success3);
280  gt_imustate.block(1, 0, 4, 1) = ov_core::quat_multiply(gt_imustate.block(1, 0, 4, 1), ov_core::rot_2_quat(R_ESTtoGT));
281  gt_imustate.block(5, 0, 3, 1) = R_ESTtoGT.transpose() * (gt_imustate.block(5, 0, 3, 1) - t_ESTinGT);
282  poseGT.header.stamp = ros::Time(_pose.first);
283  poseGT.header.frame_id = "global";
284  poseGT.pose.orientation.x = gt_imustate(1);
285  poseGT.pose.orientation.y = gt_imustate(2);
286  poseGT.pose.orientation.z = gt_imustate(3);
287  poseGT.pose.orientation.w = gt_imustate(4);
288  poseGT.pose.position.x = gt_imustate(5);
289  poseGT.pose.position.y = gt_imustate(6);
290  poseGT.pose.position.z = gt_imustate(7);
291  arrEST.poses.push_back(poseEST);
292  arrGT.poses.push_back(poseGT);
293  }
294  pub_pathimu.publish(arrEST);
295  pub_pathgt.publish(arrGT);
296 
297  // Features ESTIMATES pointcloud
298  sensor_msgs::PointCloud point_cloud;
299  point_cloud.header.frame_id = "global";
300  point_cloud.header.stamp = ros::Time::now();
301  for (auto const &featpair : _features_SLAM) {
302  geometry_msgs::Point32 p;
303  p.x = (float)featpair.second->get_xyz(false)(0, 0);
304  p.y = (float)featpair.second->get_xyz(false)(1, 0);
305  p.z = (float)featpair.second->get_xyz(false)(2, 0);
306  point_cloud.points.push_back(p);
307  }
308  pub_loop_point.publish(point_cloud);
309 
310  // Features GROUNDTRUTH pointcloud
311  sensor_msgs::PointCloud2 cloud;
312  cloud.header.frame_id = "global";
313  cloud.header.stamp = ros::Time::now();
314  cloud.width = _features_SLAM.size();
315  cloud.height = 1;
316  cloud.is_bigendian = false;
317  cloud.is_dense = false; // there may be invalid points
318  sensor_msgs::PointCloud2Modifier modifier(cloud);
319  modifier.setPointCloud2FieldsByString(1, "xyz");
320  modifier.resize(_features_SLAM.size());
321  sensor_msgs::PointCloud2Iterator<float> out_x(cloud, "x");
322  sensor_msgs::PointCloud2Iterator<float> out_y(cloud, "y");
323  sensor_msgs::PointCloud2Iterator<float> out_z(cloud, "z");
324  for (auto &featpair : _features_SLAM) {
325  // TrackSIM adds 1 to sim id if num_aruco is zero
326  Eigen::Vector3d feat = sim.get_map().at(featpair.first - 1);
327  feat = R_ESTtoGT.transpose() * (feat - t_ESTinGT);
328  *out_x = (float)feat(0);
329  ++out_x;
330  *out_y = (float)feat(1);
331  ++out_y;
332  *out_z = (float)feat(2);
333  ++out_z;
334  }
335  pub_points_sim.publish(cloud);
336 #endif
337 
338  // Wait for user approval
339  do {
340  std::cout << '\n' << "Press a key to continue...";
341  } while (std::cin.get() != '\n');
342 
343  // Reset our tracker and simulator so we can try to init again
344  if (params.sim_do_perturbation) {
345  sim.perturb_parameters(params);
346  }
347  imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
348  tracker = std::make_shared<ov_core::TrackSIM>(params.camera_intrinsics, 0);
349  initializer = std::make_shared<DynamicInitializer>(params, tracker->get_feature_database(), imu_readings);
350  } else if (timestamp != -1) {
351  PRINT_INFO(RED "failed (%.4f seconds)\n\n" RESET, time);
352  }
353  }
354  }
355 
356  // Done!
357  return EXIT_SUCCESS;
358 }
main
int main(int argc, char **argv)
Definition: test_dynamic_init.cpp:76
point_cloud2_iterator.h
ov_init::InertialInitializerOptions::camera_intrinsics
std::unordered_map< size_t, std::shared_ptr< ov_core::CamBase > > camera_intrinsics
Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)
Definition: InertialInitializerOptions.h:249
TrackSIM.h
ov_init::InertialInitializerOptions
Struct which stores all options needed for state estimation.
Definition: InertialInitializerOptions.h:49
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
get
ROSCPP_DECL bool get(const std::string &key, bool &b)
SimulatorInit.h
ov_init::InertialInitializerOptions::print_and_load_simulation
void print_and_load_simulation(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all simulated parameters. This allows for visual checking that ever...
Definition: InertialInitializerOptions.h:388
ov_core::rot_z
Eigen::Matrix< double, 3, 3 > rot_z(double t)
IMU.h
ros.h
ov_core::quat_multiply
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
PRINT_DEBUG
#define PRINT_DEBUG(x...)
REDPURPLE
#define REDPURPLE
sensor_data.h
align_posyaw_single
void align_posyaw_single(const Eigen::Vector4d &q_es_0, const Eigen::Vector3d &p_es_0, const Eigen::Vector4d &q_gt_0, const Eigen::Vector3d &p_gt_0, Eigen::Matrix3d &R, Eigen::Vector3d &t)
Definition: test_dynamic_init.cpp:65
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_init::SimulatorInit::get_map
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
Definition: SimulatorInit.h:106
ov_init::SimulatorInit::get_next_imu
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
Definition: SimulatorInit.cpp:289
ov_init::SimulatorInit::ok
bool ok()
Returns if we are actively simulating.
Definition: SimulatorInit.h:71
sensor_msgs::PointCloud2Iterator
PoseJPL.h
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
ov_init::InertialInitializerOptions::print_and_load
void print_and_load(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load the non-simulation parameters of the system and print.
Definition: InertialInitializerOptions.h:55
ov_init::InertialInitializerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU (t_imu = t_cam + t_off)
Definition: InertialInitializerOptions.h:246
ov_init::SimulatorInit::get_next_cam
bool get_next_cam(double &time_cam, std::vector< int > &camids, std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> &feats)
Gets the next inertial reading if we have one.
Definition: SimulatorInit.cpp:350
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
ov_core::ImuData::wm
Eigen::Matrix< double, 3, 1 > wm
ov_core::ImuData
GREEN
GREEN
ov_core::rot_2_quat
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
ov_core::quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
ov_init::SimulatorInit::get_true_parameters
InertialInitializerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
Definition: SimulatorInit.h:109
ov_core::ImuData::am
Eigen::Matrix< double, 3, 1 > am
signal_callback_handler
void signal_callback_handler(int signum)
Definition: test_dynamic_init.cpp:55
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
ov_init::InertialInitializerOptions::sim_do_perturbation
bool sim_do_perturbation
If we should perturb the calibration that the estimator starts with.
Definition: InertialInitializerOptions.h:361
ros::Time
colors.h
Landmark.h
sensor_msgs::PointCloud2Modifier
PRINT_INFO
#define PRINT_INFO(x...)
RESET
#define RESET
ov_init::SimulatorInit::perturb_parameters
void perturb_parameters(InertialInitializerOptions &params_)
Will get a set of perturbed parameters.
Definition: SimulatorInit.cpp:203
ov_init::SimulatorInit
Master simulator class that generated visual-inertial measurements.
Definition: SimulatorInit.h:52
InertialInitializerOptions.h
get_best_yaw
static double get_best_yaw(const Eigen::Matrix< double, 3, 3 > &C)
Definition: test_dynamic_init.cpp:58
ov_core::ImuData::timestamp
double timestamp
ov_core::log_so3
Eigen::Matrix< double, 3, 1 > log_so3(const Eigen::Matrix< double, 3, 3 > &R)
RED
RED
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
ov_init::SimulatorInit::get_state
bool get_state(double desired_time, Eigen::Matrix< double, 17, 1 > &imustate)
Get the simulation state at a specified timestep.
Definition: SimulatorInit.cpp:245
ros::Time::now
static Time now()
DynamicInitializer.h


ov_init
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51