ROS2Visualizer.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 "ROS2Visualizer.h"
23 
24 #include "core/VioManager.h"
26 #include "sim/Simulator.h"
27 #include "state/Propagator.h"
28 #include "state/State.h"
29 #include "state/StateHelper.h"
30 #include "utils/dataset_reader.h"
31 #include "utils/print.h"
32 #include "utils/sensor_data.h"
33 
34 using namespace ov_core;
35 using namespace ov_type;
36 using namespace ov_msckf;
37 
38 ROS2Visualizer::ROS2Visualizer(std::shared_ptr<rclcpp::Node> node, std::shared_ptr<VioManager> app, std::shared_ptr<Simulator> sim)
39  : _node(node), _app(app), _sim(sim), thread_update_running(false) {
40 
41  // Setup our transform broadcaster
42  mTfBr = std::make_shared<tf2_ros::TransformBroadcaster>(node);
43 
44  // Create image transport
46 
47  // Setup pose and path publisher
48  pub_poseimu = node->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>("poseimu", 2);
49  PRINT_DEBUG("Publishing: %s\n", pub_poseimu->get_topic_name());
50  pub_odomimu = node->create_publisher<nav_msgs::msg::Odometry>("odomimu", 2);
51  PRINT_DEBUG("Publishing: %s\n", pub_odomimu->get_topic_name());
52  pub_pathimu = node->create_publisher<nav_msgs::msg::Path>("pathimu", 2);
53  PRINT_DEBUG("Publishing: %s\n", pub_pathimu->get_topic_name());
54 
55  // 3D points publishing
56  pub_points_msckf = node->create_publisher<sensor_msgs::msg::PointCloud2>("points_msckf", 2);
57  PRINT_DEBUG("Publishing: %s\n", pub_points_msckf->get_topic_name());
58  pub_points_slam = node->create_publisher<sensor_msgs::msg::PointCloud2>("points_slam", 2);
59  PRINT_DEBUG("Publishing: %s\n", pub_points_msckf->get_topic_name());
60  pub_points_aruco = node->create_publisher<sensor_msgs::msg::PointCloud2>("points_aruco", 2);
61  PRINT_DEBUG("Publishing: %s\n", pub_points_aruco->get_topic_name());
62  pub_points_sim = node->create_publisher<sensor_msgs::msg::PointCloud2>("points_sim", 2);
63  PRINT_DEBUG("Publishing: %s\n", pub_points_sim->get_topic_name());
64 
65  // Our tracking image
66  it_pub_tracks = it.advertise("trackhist", 2);
67  PRINT_DEBUG("Publishing: %s\n", it_pub_tracks.getTopic().c_str());
68 
69  // Groundtruth publishers
70  pub_posegt = node->create_publisher<geometry_msgs::msg::PoseStamped>("posegt", 2);
71  PRINT_DEBUG("Publishing: %s\n", pub_posegt->get_topic_name());
72  pub_pathgt = node->create_publisher<nav_msgs::msg::Path>("pathgt", 2);
73  PRINT_DEBUG("Publishing: %s\n", pub_pathgt->get_topic_name());
74 
75  // Loop closure publishers
76  pub_loop_pose = node->create_publisher<nav_msgs::msg::Odometry>("loop_pose", 2);
77  pub_loop_point = node->create_publisher<sensor_msgs::msg::PointCloud>("loop_feats", 2);
78  pub_loop_extrinsic = node->create_publisher<nav_msgs::msg::Odometry>("loop_extrinsic", 2);
79  pub_loop_intrinsics = node->create_publisher<sensor_msgs::msg::CameraInfo>("loop_intrinsics", 2);
80  it_pub_loop_img_depth = it.advertise("loop_depth", 2);
81  it_pub_loop_img_depth_color = it.advertise("loop_depth_colored", 2);
82 
83  // option to enable publishing of global to IMU transformation
84  if (node->has_parameter("publish_global_to_imu_tf")) {
85  node->get_parameter<bool>("publish_global_to_imu_tf", publish_global2imu_tf);
86  }
87  if (node->has_parameter("publish_calibration_tf")) {
88  node->get_parameter<bool>("publish_calibration_tf", publish_calibration_tf);
89  }
90 
91  // Load groundtruth if we have it and are not doing simulation
92  // NOTE: needs to be a csv ASL format file
93  std::string path_to_gt;
94  bool has_gt = node->get_parameter("path_gt", path_to_gt);
95  if (has_gt && _sim == nullptr && !path_to_gt.empty()) {
96  DatasetReader::load_gt_file(path_to_gt, gt_states);
97  PRINT_DEBUG("gt file path is: %s\n", path_to_gt.c_str());
98  }
99 
100  // Load if we should save the total state to file
101  // If so, then open the file and create folders as needed
102  if (node->has_parameter("save_total_state")) {
103  node->get_parameter<bool>("save_total_state", save_total_state);
104  }
105  if (save_total_state) {
106 
107  // files we will open
108  std::string filepath_est = "state_estimate.txt";
109  std::string filepath_std = "state_deviation.txt";
110  std::string filepath_gt = "state_groundtruth.txt";
111  if (node->has_parameter("filepath_est")) {
112  node->get_parameter<std::string>("filepath_est", filepath_est);
113  }
114  if (node->has_parameter("filepath_std")) {
115  node->get_parameter<std::string>("filepath_std", filepath_std);
116  }
117  if (node->has_parameter("filepath_gt")) {
118  node->get_parameter<std::string>("filepath_gt", filepath_gt);
119  }
120 
121  // If it exists, then delete it
122  if (boost::filesystem::exists(filepath_est))
123  boost::filesystem::remove(filepath_est);
124  if (boost::filesystem::exists(filepath_std))
125  boost::filesystem::remove(filepath_std);
126 
127  // Create folder path to this location if not exists
128  boost::filesystem::create_directories(boost::filesystem::path(filepath_est.c_str()).parent_path());
129  boost::filesystem::create_directories(boost::filesystem::path(filepath_std.c_str()).parent_path());
130 
131  // Open the files
132  of_state_est.open(filepath_est.c_str());
133  of_state_std.open(filepath_std.c_str());
134  of_state_est << "# timestamp(s) q p v bg ba cam_imu_dt num_cam cam0_k cam0_d cam0_rot cam0_trans ... imu_model dw da tg wtoI atoI etc"
135  << std::endl;
136  of_state_std << "# timestamp(s) q p v bg ba cam_imu_dt num_cam cam0_k cam0_d cam0_rot cam0_trans ... imu_model dw da tg wtoI atoI etc"
137  << std::endl;
138 
139  // Groundtruth if we are simulating
140  if (_sim != nullptr) {
141  if (boost::filesystem::exists(filepath_gt))
142  boost::filesystem::remove(filepath_gt);
143  boost::filesystem::create_directories(boost::filesystem::path(filepath_gt.c_str()).parent_path());
144  of_state_gt.open(filepath_gt.c_str());
145  of_state_gt << "# timestamp(s) q p v bg ba cam_imu_dt num_cam cam0_k cam0_d cam0_rot cam0_trans ... imu_model dw da tg wtoI atoI etc"
146  << std::endl;
147  }
148  }
149 
150  // Start thread for the image publishing
151  if (_app->get_params().use_multi_threading_pubs) {
152  std::thread thread([&] {
153  rclcpp::Rate loop_rate(20);
154  while (rclcpp::ok()) {
155  publish_images();
156  loop_rate.sleep();
157  }
158  });
159  thread.detach();
160  }
161 }
162 
163 void ROS2Visualizer::setup_subscribers(std::shared_ptr<ov_core::YamlParser> parser) {
164 
165  // We need a valid parser
166  assert(parser != nullptr);
167 
168  // Create imu subscriber (handle legacy ros param info)
169  std::string topic_imu;
170  _node->declare_parameter<std::string>("topic_imu", "/imu0");
171  _node->get_parameter("topic_imu", topic_imu);
172  parser->parse_external("relative_config_imu", "imu0", "rostopic", topic_imu);
173  sub_imu = _node->create_subscription<sensor_msgs::msg::Imu>(topic_imu, rclcpp::SensorDataQoS(),
174  std::bind(&ROS2Visualizer::callback_inertial, this, std::placeholders::_1));
175  PRINT_INFO("subscribing to IMU: %s\n", topic_imu.c_str());
176 
177  // Logic for sync stereo subscriber
178  // https://answers.ros.org/question/96346/subscribe-to-two-image_raws-with-one-function/?answer=96491#post-id-96491
179  if (_app->get_params().state_options.num_cameras == 2) {
180  // Read in the topics
181  std::string cam_topic0, cam_topic1;
182  _node->declare_parameter<std::string>("topic_camera" + std::to_string(0), "/cam" + std::to_string(0) + "/image_raw");
183  _node->get_parameter("topic_camera" + std::to_string(0), cam_topic0);
184  _node->declare_parameter<std::string>("topic_camera" + std::to_string(1), "/cam" + std::to_string(1) + "/image_raw");
185  _node->get_parameter("topic_camera" + std::to_string(1), cam_topic1);
186  parser->parse_external("relative_config_imucam", "cam" + std::to_string(0), "rostopic", cam_topic0);
187  parser->parse_external("relative_config_imucam", "cam" + std::to_string(1), "rostopic", cam_topic1);
188  // Create sync filter (they have unique pointers internally, so we have to use move logic here...)
189  auto image_sub0 = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::Image>>(_node, cam_topic0);
190  auto image_sub1 = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::Image>>(_node, cam_topic1);
191  auto sync = std::make_shared<message_filters::Synchronizer<sync_pol>>(sync_pol(10), *image_sub0, *image_sub1);
192  sync->registerCallback(std::bind(&ROS2Visualizer::callback_stereo, this, std::placeholders::_1, std::placeholders::_2, 0, 1));
193  // sync->registerCallback([](const sensor_msgs::msg::Image::SharedPtr msg0, const sensor_msgs::msg::Image::SharedPtr msg1)
194  // {callback_stereo(msg0, msg1, 0, 1);});
195  // sync->registerCallback(&callback_stereo2); // since the above two alternatives fail to compile for some reason
196  // Append to our vector of subscribers
197  sync_cam.push_back(sync);
198  sync_subs_cam.push_back(image_sub0);
199  sync_subs_cam.push_back(image_sub1);
200  PRINT_INFO("subscribing to cam (stereo): %s\n", cam_topic0.c_str());
201  PRINT_INFO("subscribing to cam (stereo): %s\n", cam_topic1.c_str());
202  } else {
203  // Now we should add any non-stereo callbacks here
204  for (int i = 0; i < _app->get_params().state_options.num_cameras; i++) {
205  // read in the topic
206  std::string cam_topic;
207  _node->declare_parameter<std::string>("topic_camera" + std::to_string(i), "/cam" + std::to_string(i) + "/image_raw");
208  _node->get_parameter("topic_camera" + std::to_string(i), cam_topic);
209  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "rostopic", cam_topic);
210  // create subscriber
211  // auto sub = _node->create_subscription<sensor_msgs::msg::Image>(
212  // cam_topic, rclcpp::SensorDataQoS(), std::bind(&ROS2Visualizer::callback_monocular, this, std::placeholders::_1, i));
213  auto sub = _node->create_subscription<sensor_msgs::msg::Image>(
214  cam_topic, 10, [this, i](const sensor_msgs::msg::Image::SharedPtr msg0) { callback_monocular(msg0, i); });
215  subs_cam.push_back(sub);
216  PRINT_INFO("subscribing to cam (mono): %s\n", cam_topic.c_str());
217  }
218  }
219 }
220 
222 
223  // Return if we have already visualized
224  if (last_visualization_timestamp == _app->get_state()->_timestamp && _app->initialized())
225  return;
226  last_visualization_timestamp = _app->get_state()->_timestamp;
227 
228  // Start timing
229  // boost::posix_time::ptime rT0_1, rT0_2;
230  // rT0_1 = boost::posix_time::microsec_clock::local_time();
231 
232  // publish current image (only if not multi-threaded)
233  if (!_app->get_params().use_multi_threading_pubs)
234  publish_images();
235 
236  // Return if we have not inited
237  if (!_app->initialized())
238  return;
239 
240  // Save the start time of this dataset
241  if (!start_time_set) {
242  rT1 = boost::posix_time::microsec_clock::local_time();
243  start_time_set = true;
244  }
245 
246  // publish state
247  publish_state();
248 
249  // publish points
251 
252  // Publish gt if we have it
254 
255  // Publish keyframe information
257 
258  // Save total state
259  if (save_total_state) {
261  }
262 
263  // Print how much time it took to publish / displaying things
264  // rT0_2 = boost::posix_time::microsec_clock::local_time();
265  // double time_total = (rT0_2 - rT0_1).total_microseconds() * 1e-6;
266  // PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for visualization\n" RESET, time_total);
267 }
268 
269 void ROS2Visualizer::visualize_odometry(double timestamp) {
270 
271  // Return if we have not inited and a second has passes
272  if (!_app->initialized() || (timestamp - _app->initialized_time()) < 1)
273  return;
274 
275  // Get fast propagate state at the desired timestamp
276  std::shared_ptr<State> state = _app->get_state();
277  Eigen::Matrix<double, 13, 1> state_plus = Eigen::Matrix<double, 13, 1>::Zero();
278  Eigen::Matrix<double, 12, 12> cov_plus = Eigen::Matrix<double, 12, 12>::Zero();
279  if (!_app->get_propagator()->fast_state_propagate(state, timestamp, state_plus, cov_plus))
280  return;
281 
282  // Publish our odometry message if requested
283  if (pub_odomimu->get_subscription_count() != 0) {
284 
285  // Our odometry message
286  nav_msgs::msg::Odometry odomIinM;
287  odomIinM.header.stamp = ROSVisualizerHelper::get_time_from_seconds(timestamp);
288  odomIinM.header.frame_id = "global";
289 
290  // The POSE component (orientation and position)
291  odomIinM.pose.pose.orientation.x = state_plus(0);
292  odomIinM.pose.pose.orientation.y = state_plus(1);
293  odomIinM.pose.pose.orientation.z = state_plus(2);
294  odomIinM.pose.pose.orientation.w = state_plus(3);
295  odomIinM.pose.pose.position.x = state_plus(4);
296  odomIinM.pose.pose.position.y = state_plus(5);
297  odomIinM.pose.pose.position.z = state_plus(6);
298 
299  // The TWIST component (angular and linear velocities)
300  odomIinM.child_frame_id = "imu";
301  odomIinM.twist.twist.linear.x = state_plus(7); // vel in local frame
302  odomIinM.twist.twist.linear.y = state_plus(8); // vel in local frame
303  odomIinM.twist.twist.linear.z = state_plus(9); // vel in local frame
304  odomIinM.twist.twist.angular.x = state_plus(10); // we do not estimate this...
305  odomIinM.twist.twist.angular.y = state_plus(11); // we do not estimate this...
306  odomIinM.twist.twist.angular.z = state_plus(12); // we do not estimate this...
307 
308  // Finally set the covariance in the message (in the order position then orientation as per ros convention)
309  Eigen::Matrix<double, 12, 12> Phi = Eigen::Matrix<double, 12, 12>::Zero();
310  Phi.block(0, 3, 3, 3).setIdentity();
311  Phi.block(3, 0, 3, 3).setIdentity();
312  Phi.block(6, 6, 6, 6).setIdentity();
313  cov_plus = Phi * cov_plus * Phi.transpose();
314  for (int r = 0; r < 6; r++) {
315  for (int c = 0; c < 6; c++) {
316  odomIinM.pose.covariance[6 * r + c] = cov_plus(r, c);
317  }
318  }
319  for (int r = 0; r < 6; r++) {
320  for (int c = 0; c < 6; c++) {
321  odomIinM.twist.covariance[6 * r + c] = cov_plus(r + 6, c + 6);
322  }
323  }
324  pub_odomimu->publish(odomIinM);
325  }
326 
327  // Publish our transform on TF
328  // NOTE: since we use JPL we have an implicit conversion to Hamilton when we publish
329  // NOTE: a rotation from GtoI in JPL has the same xyzw as a ItoG Hamilton rotation
330  auto odom_pose = std::make_shared<ov_type::PoseJPL>();
331  odom_pose->set_value(state_plus.block(0, 0, 7, 1));
332  geometry_msgs::msg::TransformStamped trans = ROSVisualizerHelper::get_stamped_transform_from_pose(_node, odom_pose, false);
333  trans.header.stamp = _node->now();
334  trans.header.frame_id = "global";
335  trans.child_frame_id = "imu";
336  if (publish_global2imu_tf) {
337  mTfBr->sendTransform(trans);
338  }
339 
340  // Loop through each camera calibration and publish it
341  for (const auto &calib : state->_calib_IMUtoCAM) {
342  geometry_msgs::msg::TransformStamped trans_calib = ROSVisualizerHelper::get_stamped_transform_from_pose(_node, calib.second, true);
343  trans_calib.header.stamp = _node->now();
344  trans_calib.header.frame_id = "imu";
345  trans_calib.child_frame_id = "cam" + std::to_string(calib.first);
347  mTfBr->sendTransform(trans_calib);
348  }
349  }
350 }
351 
353 
354  // Final time offset value
355  if (_app->get_state()->_options.do_calib_camera_timeoffset) {
356  PRINT_INFO(REDPURPLE "camera-imu timeoffset = %.5f\n\n" RESET, _app->get_state()->_calib_dt_CAMtoIMU->value()(0));
357  }
358 
359  // Final camera intrinsics
360  if (_app->get_state()->_options.do_calib_camera_intrinsics) {
361  for (int i = 0; i < _app->get_state()->_options.num_cameras; i++) {
362  std::shared_ptr<Vec> calib = _app->get_state()->_cam_intrinsics.at(i);
363  PRINT_INFO(REDPURPLE "cam%d intrinsics:\n" RESET, (int)i);
364  PRINT_INFO(REDPURPLE "%.3f,%.3f,%.3f,%.3f\n" RESET, calib->value()(0), calib->value()(1), calib->value()(2), calib->value()(3));
365  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,%.5f\n\n" RESET, calib->value()(4), calib->value()(5), calib->value()(6), calib->value()(7));
366  }
367  }
368 
369  // Final camera extrinsics
370  if (_app->get_state()->_options.do_calib_camera_pose) {
371  for (int i = 0; i < _app->get_state()->_options.num_cameras; i++) {
372  std::shared_ptr<PoseJPL> calib = _app->get_state()->_calib_IMUtoCAM.at(i);
373  Eigen::Matrix4d T_CtoI = Eigen::Matrix4d::Identity();
374  T_CtoI.block(0, 0, 3, 3) = quat_2_Rot(calib->quat()).transpose();
375  T_CtoI.block(0, 3, 3, 1) = -T_CtoI.block(0, 0, 3, 3) * calib->pos();
376  PRINT_INFO(REDPURPLE "T_C%dtoI:\n" RESET, i);
377  PRINT_INFO(REDPURPLE "%.3f,%.3f,%.3f,%.3f,\n" RESET, T_CtoI(0, 0), T_CtoI(0, 1), T_CtoI(0, 2), T_CtoI(0, 3));
378  PRINT_INFO(REDPURPLE "%.3f,%.3f,%.3f,%.3f,\n" RESET, T_CtoI(1, 0), T_CtoI(1, 1), T_CtoI(1, 2), T_CtoI(1, 3));
379  PRINT_INFO(REDPURPLE "%.3f,%.3f,%.3f,%.3f,\n" RESET, T_CtoI(2, 0), T_CtoI(2, 1), T_CtoI(2, 2), T_CtoI(2, 3));
380  PRINT_INFO(REDPURPLE "%.3f,%.3f,%.3f,%.3f\n\n" RESET, T_CtoI(3, 0), T_CtoI(3, 1), T_CtoI(3, 2), T_CtoI(3, 3));
381  }
382  }
383 
384  // IMU intrinsics
385  if (_app->get_state()->_options.do_calib_imu_intrinsics) {
386  Eigen::Matrix3d Dw = State::Dm(_app->get_state()->_options.imu_model, _app->get_state()->_calib_imu_dw->value());
387  Eigen::Matrix3d Da = State::Dm(_app->get_state()->_options.imu_model, _app->get_state()->_calib_imu_da->value());
388  Eigen::Matrix3d Tw = Dw.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
389  Eigen::Matrix3d Ta = Da.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
390  Eigen::Matrix3d R_IMUtoACC = _app->get_state()->_calib_imu_ACCtoIMU->Rot().transpose();
391  Eigen::Matrix3d R_IMUtoGYRO = _app->get_state()->_calib_imu_GYROtoIMU->Rot().transpose();
392  PRINT_INFO(REDPURPLE "Tw:\n" RESET);
393  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, Tw(0, 0), Tw(0, 1), Tw(0, 2));
394  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, Tw(1, 0), Tw(1, 1), Tw(1, 2));
395  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f\n\n" RESET, Tw(2, 0), Tw(2, 1), Tw(2, 2));
396  PRINT_INFO(REDPURPLE "Ta:\n" RESET);
397  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, Ta(0, 0), Ta(0, 1), Ta(0, 2));
398  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, Ta(1, 0), Ta(1, 1), Ta(1, 2));
399  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f\n\n" RESET, Ta(2, 0), Ta(2, 1), Ta(2, 2));
400  PRINT_INFO(REDPURPLE "R_IMUtoACC:\n" RESET);
401  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, R_IMUtoACC(0, 0), R_IMUtoACC(0, 1), R_IMUtoACC(0, 2));
402  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, R_IMUtoACC(1, 0), R_IMUtoACC(1, 1), R_IMUtoACC(1, 2));
403  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f\n\n" RESET, R_IMUtoACC(2, 0), R_IMUtoACC(2, 1), R_IMUtoACC(2, 2));
404  PRINT_INFO(REDPURPLE "R_IMUtoGYRO:\n" RESET);
405  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, R_IMUtoGYRO(0, 0), R_IMUtoGYRO(0, 1), R_IMUtoGYRO(0, 2));
406  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f,\n" RESET, R_IMUtoGYRO(1, 0), R_IMUtoGYRO(1, 1), R_IMUtoGYRO(1, 2));
407  PRINT_INFO(REDPURPLE "%.5f,%.5f,%.5f\n\n" RESET, R_IMUtoGYRO(2, 0), R_IMUtoGYRO(2, 1), R_IMUtoGYRO(2, 2));
408  }
409 
410  // IMU intrinsics gravity sensitivity
411  if (_app->get_state()->_options.do_calib_imu_g_sensitivity) {
412  Eigen::Matrix3d Tg = State::Tg(_app->get_state()->_calib_imu_tg->value());
413  PRINT_INFO(REDPURPLE "Tg:\n" RESET);
414  PRINT_INFO(REDPURPLE "%.6f,%.6f,%.6f,\n" RESET, Tg(0, 0), Tg(0, 1), Tg(0, 2));
415  PRINT_INFO(REDPURPLE "%.6f,%.6f,%.6f,\n" RESET, Tg(1, 0), Tg(1, 1), Tg(1, 2));
416  PRINT_INFO(REDPURPLE "%.6f,%.6f,%.6f\n\n" RESET, Tg(2, 0), Tg(2, 1), Tg(2, 2));
417  }
418 
419  // Publish RMSE if we have it
420  if (!gt_states.empty()) {
421  PRINT_INFO(REDPURPLE "RMSE: %.3f (deg) orientation\n" RESET, std::sqrt(summed_mse_ori / summed_number));
422  PRINT_INFO(REDPURPLE "RMSE: %.3f (m) position\n\n" RESET, std::sqrt(summed_mse_pos / summed_number));
423  }
424 
425  // Publish RMSE and NEES if doing simulation
426  if (_sim != nullptr) {
427  PRINT_INFO(REDPURPLE "RMSE: %.3f (deg) orientation\n" RESET, std::sqrt(summed_mse_ori / summed_number));
428  PRINT_INFO(REDPURPLE "RMSE: %.3f (m) position\n\n" RESET, std::sqrt(summed_mse_pos / summed_number));
429  PRINT_INFO(REDPURPLE "NEES: %.3f (deg) orientation\n" RESET, summed_nees_ori / summed_number);
430  PRINT_INFO(REDPURPLE "NEES: %.3f (m) position\n\n" RESET, summed_nees_pos / summed_number);
431  }
432 
433  // Print the total time
434  rT2 = boost::posix_time::microsec_clock::local_time();
435  PRINT_INFO(REDPURPLE "TIME: %.3f seconds\n\n" RESET, (rT2 - rT1).total_microseconds() * 1e-6);
436 }
437 
438 void ROS2Visualizer::callback_inertial(const sensor_msgs::msg::Imu::SharedPtr msg) {
439 
440  // convert into correct format
441  ov_core::ImuData message;
442  message.timestamp = msg->header.stamp.sec + msg->header.stamp.nanosec * 1e-9;
443  message.wm << msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z;
444  message.am << msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z;
445 
446  // send it to our VIO system
447  _app->feed_measurement_imu(message);
448  visualize_odometry(message.timestamp);
449 
450  // If the processing queue is currently active / running just return so we can keep getting measurements
451  // Otherwise create a second thread to do our update in an async manor
452  // The visualization of the state, images, and features will be synchronous with the update!
454  return;
455  thread_update_running = true;
456  std::thread thread([&] {
457  // Lock on the queue (prevents new images from appending)
458  std::lock_guard<std::mutex> lck(camera_queue_mtx);
459 
460  // Count how many unique image streams
461  std::map<int, bool> unique_cam_ids;
462  for (const auto &cam_msg : camera_queue) {
463  unique_cam_ids[cam_msg.sensor_ids.at(0)] = true;
464  }
465 
466  // If we do not have enough unique cameras then we need to wait
467  // We should wait till we have one of each camera to ensure we propagate in the correct order
468  auto params = _app->get_params();
469  size_t num_unique_cameras = (params.state_options.num_cameras == 2) ? 1 : params.state_options.num_cameras;
470  if (unique_cam_ids.size() == num_unique_cameras) {
471 
472  // Loop through our queue and see if we are able to process any of our camera measurements
473  // We are able to process if we have at least one IMU measurement greater than the camera time
474  double timestamp_imu_inC = message.timestamp - _app->get_state()->_calib_dt_CAMtoIMU->value()(0);
475  while (!camera_queue.empty() && camera_queue.at(0).timestamp < timestamp_imu_inC) {
476  auto rT0_1 = boost::posix_time::microsec_clock::local_time();
477  double update_dt = 100.0 * (timestamp_imu_inC - camera_queue.at(0).timestamp);
478  _app->feed_measurement_camera(camera_queue.at(0));
479  visualize();
480  camera_queue.pop_front();
481  auto rT0_2 = boost::posix_time::microsec_clock::local_time();
482  double time_total = (rT0_2 - rT0_1).total_microseconds() * 1e-6;
483  PRINT_INFO(BLUE "[TIME]: %.4f seconds total (%.1f hz, %.2f ms behind)\n" RESET, time_total, 1.0 / time_total, update_dt);
484  }
485  }
486  thread_update_running = false;
487  });
488 
489  // If we are single threaded, then run single threaded
490  // Otherwise detach this thread so it runs in the background!
491  if (!_app->get_params().use_multi_threading_subs) {
492  thread.join();
493  } else {
494  thread.detach();
495  }
496 }
497 
498 void ROS2Visualizer::callback_monocular(const sensor_msgs::msg::Image::SharedPtr msg0, int cam_id0) {
499 
500  // Check if we should drop this image
501  double timestamp = msg0->header.stamp.sec + msg0->header.stamp.nanosec * 1e-9;
502  double time_delta = 1.0 / _app->get_params().track_frequency;
503  if (camera_last_timestamp.find(cam_id0) != camera_last_timestamp.end() && timestamp < camera_last_timestamp.at(cam_id0) + time_delta) {
504  return;
505  }
506  camera_last_timestamp[cam_id0] = timestamp;
507 
508  // Get the image
510  try {
512  } catch (cv_bridge::Exception &e) {
513  PRINT_ERROR("cv_bridge exception: %s", e.what());
514  return;
515  }
516 
517  // Create the measurement
518  ov_core::CameraData message;
519  message.timestamp = cv_ptr->header.stamp.sec + cv_ptr->header.stamp.nanosec * 1e-9;
520  message.sensor_ids.push_back(cam_id0);
521  message.images.push_back(cv_ptr->image.clone());
522 
523  // Load the mask if we are using it, else it is empty
524  // TODO: in the future we should get this from external pixel segmentation
525  if (_app->get_params().use_mask) {
526  message.masks.push_back(_app->get_params().masks.at(cam_id0));
527  } else {
528  message.masks.push_back(cv::Mat::zeros(cv_ptr->image.rows, cv_ptr->image.cols, CV_8UC1));
529  }
530 
531  // append it to our queue of images
532  std::lock_guard<std::mutex> lck(camera_queue_mtx);
533  camera_queue.push_back(message);
534  std::sort(camera_queue.begin(), camera_queue.end());
535 }
536 
537 void ROS2Visualizer::callback_stereo(const sensor_msgs::msg::Image::ConstSharedPtr msg0, const sensor_msgs::msg::Image::ConstSharedPtr msg1,
538  int cam_id0, int cam_id1) {
539 
540  // Check if we should drop this image
541  double timestamp = msg0->header.stamp.sec + msg0->header.stamp.nanosec * 1e-9;
542  double time_delta = 1.0 / _app->get_params().track_frequency;
543  if (camera_last_timestamp.find(cam_id0) != camera_last_timestamp.end() && timestamp < camera_last_timestamp.at(cam_id0) + time_delta) {
544  return;
545  }
546  camera_last_timestamp[cam_id0] = timestamp;
547 
548  // Get the image
550  try {
552  } catch (cv_bridge::Exception &e) {
553  PRINT_ERROR("cv_bridge exception: %s", e.what());
554  return;
555  }
556 
557  // Get the image
559  try {
561  } catch (cv_bridge::Exception &e) {
562  PRINT_ERROR("cv_bridge exception: %s", e.what());
563  return;
564  }
565 
566  // Create the measurement
567  ov_core::CameraData message;
568  message.timestamp = cv_ptr0->header.stamp.sec + cv_ptr0->header.stamp.nanosec * 1e-9;
569  message.sensor_ids.push_back(cam_id0);
570  message.sensor_ids.push_back(cam_id1);
571  message.images.push_back(cv_ptr0->image.clone());
572  message.images.push_back(cv_ptr1->image.clone());
573 
574  // Load the mask if we are using it, else it is empty
575  // TODO: in the future we should get this from external pixel segmentation
576  if (_app->get_params().use_mask) {
577  message.masks.push_back(_app->get_params().masks.at(cam_id0));
578  message.masks.push_back(_app->get_params().masks.at(cam_id1));
579  } else {
580  // message.masks.push_back(cv::Mat(cv_ptr0->image.rows, cv_ptr0->image.cols, CV_8UC1, cv::Scalar(255)));
581  message.masks.push_back(cv::Mat::zeros(cv_ptr0->image.rows, cv_ptr0->image.cols, CV_8UC1));
582  message.masks.push_back(cv::Mat::zeros(cv_ptr1->image.rows, cv_ptr1->image.cols, CV_8UC1));
583  }
584 
585  // append it to our queue of images
586  std::lock_guard<std::mutex> lck(camera_queue_mtx);
587  camera_queue.push_back(message);
588  std::sort(camera_queue.begin(), camera_queue.end());
589 }
590 
592 
593  // Get the current state
594  std::shared_ptr<State> state = _app->get_state();
595 
596  // We want to publish in the IMU clock frame
597  // The timestamp in the state will be the last camera time
598  double t_ItoC = state->_calib_dt_CAMtoIMU->value()(0);
599  double timestamp_inI = state->_timestamp + t_ItoC;
600 
601  // Create pose of IMU (note we use the bag time)
602  geometry_msgs::msg::PoseWithCovarianceStamped poseIinM;
603  poseIinM.header.stamp = ROSVisualizerHelper::get_time_from_seconds(timestamp_inI);
604  poseIinM.header.frame_id = "global";
605  poseIinM.pose.pose.orientation.x = state->_imu->quat()(0);
606  poseIinM.pose.pose.orientation.y = state->_imu->quat()(1);
607  poseIinM.pose.pose.orientation.z = state->_imu->quat()(2);
608  poseIinM.pose.pose.orientation.w = state->_imu->quat()(3);
609  poseIinM.pose.pose.position.x = state->_imu->pos()(0);
610  poseIinM.pose.pose.position.y = state->_imu->pos()(1);
611  poseIinM.pose.pose.position.z = state->_imu->pos()(2);
612 
613  // Finally set the covariance in the message (in the order position then orientation as per ros convention)
614  std::vector<std::shared_ptr<Type>> statevars;
615  statevars.push_back(state->_imu->pose()->p());
616  statevars.push_back(state->_imu->pose()->q());
617  Eigen::Matrix<double, 6, 6> covariance_posori = StateHelper::get_marginal_covariance(_app->get_state(), statevars);
618  for (int r = 0; r < 6; r++) {
619  for (int c = 0; c < 6; c++) {
620  poseIinM.pose.covariance[6 * r + c] = covariance_posori(r, c);
621  }
622  }
623  pub_poseimu->publish(poseIinM);
624 
625  //=========================================================
626  //=========================================================
627 
628  // Append to our pose vector
629  geometry_msgs::msg::PoseStamped posetemp;
630  posetemp.header = poseIinM.header;
631  posetemp.pose = poseIinM.pose.pose;
632  poses_imu.push_back(posetemp);
633 
634  // Create our path (imu)
635  // NOTE: We downsample the number of poses as needed to prevent rviz crashes
636  // NOTE: https://github.com/ros-visualization/rviz/issues/1107
637  nav_msgs::msg::Path arrIMU;
638  arrIMU.header.stamp = _node->now();
639  arrIMU.header.frame_id = "global";
640  for (size_t i = 0; i < poses_imu.size(); i += std::floor((double)poses_imu.size() / 16384.0) + 1) {
641  arrIMU.poses.push_back(poses_imu.at(i));
642  }
643  pub_pathimu->publish(arrIMU);
644 }
645 
647 
648  // Return if we have already visualized
649  if (_app->get_state() == nullptr)
650  return;
651  if (last_visualization_timestamp_image == _app->get_state()->_timestamp && _app->initialized())
652  return;
653  last_visualization_timestamp_image = _app->get_state()->_timestamp;
654 
655  // Check if we have subscribers
656  if (it_pub_tracks.getNumSubscribers() == 0)
657  return;
658 
659  // Get our image of history tracks
660  cv::Mat img_history = _app->get_historical_viz_image();
661  if (img_history.empty())
662  return;
663 
664  // Create our message
665  std_msgs::msg::Header header;
666  header.stamp = _node->now();
667  header.frame_id = "cam0";
668  sensor_msgs::msg::Image::SharedPtr exl_msg = cv_bridge::CvImage(header, "bgr8", img_history).toImageMsg();
669 
670  // Publish
671  it_pub_tracks.publish(exl_msg);
672 }
673 
675 
676  // Check if we have subscribers
677  if (pub_points_msckf->get_subscription_count() == 0 && pub_points_slam->get_subscription_count() == 0 &&
678  pub_points_aruco->get_subscription_count() == 0 && pub_points_sim->get_subscription_count() == 0)
679  return;
680 
681  // Get our good MSCKF features
682  std::vector<Eigen::Vector3d> feats_msckf = _app->get_good_features_MSCKF();
683  sensor_msgs::msg::PointCloud2 cloud = ROSVisualizerHelper::get_ros_pointcloud(_node, feats_msckf);
684  pub_points_msckf->publish(cloud);
685 
686  // Get our good SLAM features
687  std::vector<Eigen::Vector3d> feats_slam = _app->get_features_SLAM();
688  sensor_msgs::msg::PointCloud2 cloud_SLAM = ROSVisualizerHelper::get_ros_pointcloud(_node, feats_slam);
689  pub_points_slam->publish(cloud_SLAM);
690 
691  // Get our good ARUCO features
692  std::vector<Eigen::Vector3d> feats_aruco = _app->get_features_ARUCO();
693  sensor_msgs::msg::PointCloud2 cloud_ARUCO = ROSVisualizerHelper::get_ros_pointcloud(_node, feats_aruco);
694  pub_points_aruco->publish(cloud_ARUCO);
695 
696  // Skip the rest of we are not doing simulation
697  if (_sim == nullptr)
698  return;
699 
700  // Get our good SIMULATION features
701  std::vector<Eigen::Vector3d> feats_sim = _sim->get_map_vec();
702  sensor_msgs::msg::PointCloud2 cloud_SIM = ROSVisualizerHelper::get_ros_pointcloud(_node, feats_sim);
703  pub_points_sim->publish(cloud_SIM);
704 }
705 
707 
708  // Our groundtruth state
709  Eigen::Matrix<double, 17, 1> state_gt;
710 
711  // We want to publish in the IMU clock frame
712  // The timestamp in the state will be the last camera time
713  double t_ItoC = _app->get_state()->_calib_dt_CAMtoIMU->value()(0);
714  double timestamp_inI = _app->get_state()->_timestamp + t_ItoC;
715 
716  // Check that we have the timestamp in our GT file [time(sec),q_GtoI,p_IinG,v_IinG,b_gyro,b_accel]
717  if (_sim == nullptr && (gt_states.empty() || !DatasetReader::get_gt_state(timestamp_inI, state_gt, gt_states))) {
718  return;
719  }
720 
721  // Get the simulated groundtruth
722  // NOTE: we get the true time in the IMU clock frame
723  if (_sim != nullptr) {
724  timestamp_inI = _app->get_state()->_timestamp + _sim->get_true_parameters().calib_camimu_dt;
725  if (!_sim->get_state(timestamp_inI, state_gt))
726  return;
727  }
728 
729  // Get the GT and system state state
730  Eigen::Matrix<double, 16, 1> state_ekf = _app->get_state()->_imu->value();
731 
732  // Create pose of IMU
733  geometry_msgs::msg::PoseStamped poseIinM;
734  poseIinM.header.stamp = ROSVisualizerHelper::get_time_from_seconds(timestamp_inI);
735  poseIinM.header.frame_id = "global";
736  poseIinM.pose.orientation.x = state_gt(1, 0);
737  poseIinM.pose.orientation.y = state_gt(2, 0);
738  poseIinM.pose.orientation.z = state_gt(3, 0);
739  poseIinM.pose.orientation.w = state_gt(4, 0);
740  poseIinM.pose.position.x = state_gt(5, 0);
741  poseIinM.pose.position.y = state_gt(6, 0);
742  poseIinM.pose.position.z = state_gt(7, 0);
743  pub_posegt->publish(poseIinM);
744 
745  // Append to our pose vector
746  poses_gt.push_back(poseIinM);
747 
748  // Create our path (imu)
749  // NOTE: We downsample the number of poses as needed to prevent rviz crashes
750  // NOTE: https://github.com/ros-visualization/rviz/issues/1107
751  nav_msgs::msg::Path arrIMU;
752  arrIMU.header.stamp = _node->now();
753  arrIMU.header.frame_id = "global";
754  for (size_t i = 0; i < poses_gt.size(); i += std::floor((double)poses_gt.size() / 16384.0) + 1) {
755  arrIMU.poses.push_back(poses_gt.at(i));
756  }
757  pub_pathgt->publish(arrIMU);
758 
759  // Publish our transform on TF
760  geometry_msgs::msg::TransformStamped trans;
761  trans.header.stamp = _node->now();
762  trans.header.frame_id = "global";
763  trans.child_frame_id = "truth";
764  trans.transform.rotation.x = state_gt(1, 0);
765  trans.transform.rotation.y = state_gt(2, 0);
766  trans.transform.rotation.z = state_gt(3, 0);
767  trans.transform.rotation.w = state_gt(4, 0);
768  trans.transform.translation.x = state_gt(5, 0);
769  trans.transform.translation.y = state_gt(6, 0);
770  trans.transform.translation.z = state_gt(7, 0);
771  if (publish_global2imu_tf) {
772  mTfBr->sendTransform(trans);
773  }
774 
775  //==========================================================================
776  //==========================================================================
777 
778  // Difference between positions
779  double dx = state_ekf(4, 0) - state_gt(5, 0);
780  double dy = state_ekf(5, 0) - state_gt(6, 0);
781  double dz = state_ekf(6, 0) - state_gt(7, 0);
782  double err_pos = std::sqrt(dx * dx + dy * dy + dz * dz);
783 
784  // Quaternion error
785  Eigen::Matrix<double, 4, 1> quat_gt, quat_st, quat_diff;
786  quat_gt << state_gt(1, 0), state_gt(2, 0), state_gt(3, 0), state_gt(4, 0);
787  quat_st << state_ekf(0, 0), state_ekf(1, 0), state_ekf(2, 0), state_ekf(3, 0);
788  quat_diff = quat_multiply(quat_st, Inv(quat_gt));
789  double err_ori = (180 / M_PI) * 2 * quat_diff.block(0, 0, 3, 1).norm();
790 
791  //==========================================================================
792  //==========================================================================
793 
794  // Get covariance of pose
795  std::vector<std::shared_ptr<Type>> statevars;
796  statevars.push_back(_app->get_state()->_imu->q());
797  statevars.push_back(_app->get_state()->_imu->p());
798  Eigen::Matrix<double, 6, 6> covariance = StateHelper::get_marginal_covariance(_app->get_state(), statevars);
799 
800  // Calculate NEES values
801  // NOTE: need to manually multiply things out to make static asserts work
802  // NOTE: https://github.com/rpng/open_vins/pull/226
803  // NOTE: https://github.com/rpng/open_vins/issues/236
804  // NOTE: https://gitlab.com/libeigen/eigen/-/issues/1664
805  Eigen::Vector3d quat_diff_vec = quat_diff.block(0, 0, 3, 1);
806  Eigen::Vector3d cov_vec = covariance.block(0, 0, 3, 3).inverse() * 2 * quat_diff.block(0, 0, 3, 1);
807  double ori_nees = 2 * quat_diff_vec.dot(cov_vec);
808  Eigen::Vector3d errpos = state_ekf.block(4, 0, 3, 1) - state_gt.block(5, 0, 3, 1);
809  double pos_nees = errpos.transpose() * covariance.block(3, 3, 3, 3).inverse() * errpos;
810 
811  //==========================================================================
812  //==========================================================================
813 
814  // Update our average variables
815  if (!std::isnan(ori_nees) && !std::isnan(pos_nees)) {
816  summed_mse_ori += err_ori * err_ori;
817  summed_mse_pos += err_pos * err_pos;
818  summed_nees_ori += ori_nees;
819  summed_nees_pos += pos_nees;
820  summed_number++;
821  }
822 
823  // Nice display for the user
824  PRINT_INFO(REDPURPLE "error to gt => %.3f, %.3f (deg,m) | rmse => %.3f, %.3f (deg,m) | called %d times\n" RESET, err_ori, err_pos,
825  std::sqrt(summed_mse_ori / summed_number), std::sqrt(summed_mse_pos / summed_number), (int)summed_number);
826  PRINT_INFO(REDPURPLE "nees => %.1f, %.1f (ori,pos) | avg nees = %.1f, %.1f (ori,pos)\n" RESET, ori_nees, pos_nees,
828 
829  //==========================================================================
830  //==========================================================================
831 }
832 
834 
835  // Get the current tracks in this frame
836  double active_tracks_time1 = -1;
837  double active_tracks_time2 = -1;
838  std::unordered_map<size_t, Eigen::Vector3d> active_tracks_posinG;
839  std::unordered_map<size_t, Eigen::Vector3d> active_tracks_uvd;
840  cv::Mat active_cam0_image;
841  _app->get_active_tracks(active_tracks_time1, active_tracks_posinG, active_tracks_uvd);
842  _app->get_active_image(active_tracks_time2, active_cam0_image);
843  if (active_tracks_time1 == -1)
844  return;
845  if (_app->get_state()->_clones_IMU.find(active_tracks_time1) == _app->get_state()->_clones_IMU.end())
846  return;
847  if (active_tracks_time1 != active_tracks_time2)
848  return;
849 
850  // Default header
851  std_msgs::msg::Header header;
852  header.stamp = ROSVisualizerHelper::get_time_from_seconds(active_tracks_time1);
853 
854  //======================================================
855  // Check if we have subscribers for the pose odometry, camera intrinsics, or extrinsics
856  if (pub_loop_pose->get_subscription_count() != 0 || pub_loop_extrinsic->get_subscription_count() != 0 ||
857  pub_loop_intrinsics->get_subscription_count() != 0) {
858 
859  // PUBLISH HISTORICAL POSE ESTIMATE
860  nav_msgs::msg::Odometry odometry_pose;
861  odometry_pose.header = header;
862  odometry_pose.header.frame_id = "global";
863  odometry_pose.pose.pose.position.x = _app->get_state()->_clones_IMU.at(active_tracks_time1)->pos()(0);
864  odometry_pose.pose.pose.position.y = _app->get_state()->_clones_IMU.at(active_tracks_time1)->pos()(1);
865  odometry_pose.pose.pose.position.z = _app->get_state()->_clones_IMU.at(active_tracks_time1)->pos()(2);
866  odometry_pose.pose.pose.orientation.x = _app->get_state()->_clones_IMU.at(active_tracks_time1)->quat()(0);
867  odometry_pose.pose.pose.orientation.y = _app->get_state()->_clones_IMU.at(active_tracks_time1)->quat()(1);
868  odometry_pose.pose.pose.orientation.z = _app->get_state()->_clones_IMU.at(active_tracks_time1)->quat()(2);
869  odometry_pose.pose.pose.orientation.w = _app->get_state()->_clones_IMU.at(active_tracks_time1)->quat()(3);
870  pub_loop_pose->publish(odometry_pose);
871 
872  // PUBLISH IMU TO CAMERA0 EXTRINSIC
873  // need to flip the transform to the IMU frame
874  Eigen::Vector4d q_ItoC = _app->get_state()->_calib_IMUtoCAM.at(0)->quat();
875  Eigen::Vector3d p_CinI = -_app->get_state()->_calib_IMUtoCAM.at(0)->Rot().transpose() * _app->get_state()->_calib_IMUtoCAM.at(0)->pos();
876  nav_msgs::msg::Odometry odometry_calib;
877  odometry_calib.header = header;
878  odometry_calib.header.frame_id = "imu";
879  odometry_calib.pose.pose.position.x = p_CinI(0);
880  odometry_calib.pose.pose.position.y = p_CinI(1);
881  odometry_calib.pose.pose.position.z = p_CinI(2);
882  odometry_calib.pose.pose.orientation.x = q_ItoC(0);
883  odometry_calib.pose.pose.orientation.y = q_ItoC(1);
884  odometry_calib.pose.pose.orientation.z = q_ItoC(2);
885  odometry_calib.pose.pose.orientation.w = q_ItoC(3);
886  pub_loop_extrinsic->publish(odometry_calib);
887 
888  // PUBLISH CAMERA0 INTRINSICS
889  bool is_fisheye = (std::dynamic_pointer_cast<ov_core::CamEqui>(_app->get_params().camera_intrinsics.at(0)) != nullptr);
890  sensor_msgs::msg::CameraInfo cameraparams;
891  cameraparams.header = header;
892  cameraparams.header.frame_id = "cam0";
893  cameraparams.distortion_model = is_fisheye ? "equidistant" : "plumb_bob";
894  Eigen::VectorXd cparams = _app->get_state()->_cam_intrinsics.at(0)->value();
895  cameraparams.d = {cparams(4), cparams(5), cparams(6), cparams(7)};
896  cameraparams.k = {cparams(0), 0, cparams(2), 0, cparams(1), cparams(3), 0, 0, 1};
897  pub_loop_intrinsics->publish(cameraparams);
898  }
899 
900  //======================================================
901  // PUBLISH FEATURE TRACKS IN THE GLOBAL FRAME OF REFERENCE
902  if (pub_loop_point->get_subscription_count() != 0) {
903 
904  // Construct the message
905  sensor_msgs::msg::PointCloud point_cloud;
906  point_cloud.header = header;
907  point_cloud.header.frame_id = "global";
908  for (const auto &feattimes : active_tracks_posinG) {
909 
910  // Get this feature information
911  size_t featid = feattimes.first;
912  Eigen::Vector3d uvd = Eigen::Vector3d::Zero();
913  if (active_tracks_uvd.find(featid) != active_tracks_uvd.end()) {
914  uvd = active_tracks_uvd.at(featid);
915  }
916  Eigen::Vector3d pFinG = active_tracks_posinG.at(featid);
917 
918  // Push back 3d point
919  geometry_msgs::msg::Point32 p;
920  p.x = pFinG(0);
921  p.y = pFinG(1);
922  p.z = pFinG(2);
923  point_cloud.points.push_back(p);
924 
925  // Push back the uv_norm, uv_raw, and feature id
926  // NOTE: we don't use the normalized coordinates to save time here
927  // NOTE: they will have to be re-normalized in the loop closure code
928  sensor_msgs::msg::ChannelFloat32 p_2d;
929  p_2d.values.push_back(0);
930  p_2d.values.push_back(0);
931  p_2d.values.push_back(uvd(0));
932  p_2d.values.push_back(uvd(1));
933  p_2d.values.push_back(featid);
934  point_cloud.channels.push_back(p_2d);
935  }
936  pub_loop_point->publish(point_cloud);
937  }
938 
939  //======================================================
940  // Depth images of sparse points and its colorized version
942 
943  // Create the images we will populate with the depths
944  std::pair<int, int> wh_pair = {active_cam0_image.cols, active_cam0_image.rows};
945  cv::Mat depthmap = cv::Mat::zeros(wh_pair.second, wh_pair.first, CV_16UC1);
946  cv::Mat depthmap_viz = active_cam0_image;
947 
948  // Loop through all points and append
949  for (const auto &feattimes : active_tracks_uvd) {
950 
951  // Get this feature information
952  size_t featid = feattimes.first;
953  Eigen::Vector3d uvd = active_tracks_uvd.at(featid);
954 
955  // Skip invalid points
956  double dw = 4;
957  if (uvd(0) < dw || uvd(0) > wh_pair.first - dw || uvd(1) < dw || uvd(1) > wh_pair.second - dw) {
958  continue;
959  }
960 
961  // Append the depth
962  // NOTE: scaled by 1000 to fit the 16U
963  // NOTE: access order is y,x (stupid opencv convention stuff)
964  depthmap.at<uint16_t>((int)uvd(1), (int)uvd(0)) = (uint16_t)(1000 * uvd(2));
965 
966  // Taken from LSD-SLAM codebase segment into 0-4 meter segments:
967  // https://github.com/tum-vision/lsd_slam/blob/d1e6f0e1a027889985d2e6b4c0fe7a90b0c75067/lsd_slam_core/src/util/globalFuncs.cpp#L87-L96
968  float id = 1.0f / (float)uvd(2);
969  float r = (0.0f - id) * 255 / 1.0f;
970  if (r < 0)
971  r = -r;
972  float g = (1.0f - id) * 255 / 1.0f;
973  if (g < 0)
974  g = -g;
975  float b = (2.0f - id) * 255 / 1.0f;
976  if (b < 0)
977  b = -b;
978  uchar rc = r < 0 ? 0 : (r > 255 ? 255 : r);
979  uchar gc = g < 0 ? 0 : (g > 255 ? 255 : g);
980  uchar bc = b < 0 ? 0 : (b > 255 ? 255 : b);
981  cv::Scalar color(255 - rc, 255 - gc, 255 - bc);
982 
983  // Small square around the point (note the above bound check needs to take into account this width)
984  cv::Point p0(uvd(0) - dw, uvd(1) - dw);
985  cv::Point p1(uvd(0) + dw, uvd(1) + dw);
986  cv::rectangle(depthmap_viz, p0, p1, color, -1);
987  }
988 
989  // Create our messages
990  header.frame_id = "cam0";
991  sensor_msgs::msg::Image::SharedPtr exl_msg1 =
993  it_pub_loop_img_depth.publish(exl_msg1);
994  header.stamp = _node->now();
995  header.frame_id = "cam0";
996  sensor_msgs::msg::Image::SharedPtr exl_msg2 = cv_bridge::CvImage(header, "bgr8", depthmap_viz).toImageMsg();
998  }
999 }
ov_msckf::ROS2Visualizer::publish_calibration_tf
bool publish_calibration_tf
Definition: ROS2Visualizer.h:204
Propagator.h
ov_msckf::ROS2Visualizer::of_state_gt
std::ofstream of_state_gt
Definition: ROS2Visualizer.h:208
ov_msckf::ROS2Visualizer::_sim
std::shared_ptr< Simulator > _sim
Simulator (is nullptr if we are not sim'ing)
Definition: ROS2Visualizer.h:145
image_transport::Publisher::getTopic
std::string getTopic() const
ov_msckf::ROS2Visualizer::sync_pol
message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image > sync_pol
Definition: ROS2Visualizer.h:161
ov_msckf::ROS2Visualizer::camera_queue_mtx
std::mutex camera_queue_mtx
Definition: ROS2Visualizer.h:189
image_transport::ImageTransport
ov_msckf::ROS2Visualizer::thread_update_running
std::atomic< bool > thread_update_running
Definition: ROS2Visualizer.h:182
boost::shared_ptr
ov_msckf::State::Dm
static Eigen::Matrix3d Dm(StateOptions::ImuModel imu_model, const Eigen::MatrixXd &vec)
Gyroscope and accelerometer intrinsic matrix (scale imperfection and axis misalignment)
Definition: State.h:91
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ov_msckf::ROS2Visualizer::poses_imu
std::vector< geometry_msgs::msg::PoseStamped > poses_imu
Definition: ROS2Visualizer.h:166
ov_msckf::ROS2Visualizer::camera_last_timestamp
std::map< int, double > camera_last_timestamp
Definition: ROS2Visualizer.h:192
ov_msckf::ROS2Visualizer::it_pub_loop_img_depth
image_transport::Publisher it_pub_loop_img_depth
Definition: ROS2Visualizer.h:148
ROSVisualizerHelper.h
ov_core::CameraData::images
std::vector< cv::Mat > images
ov_msckf::ROS2Visualizer::summed_nees_pos
double summed_nees_pos
Definition: ROS2Visualizer.h:174
ov_msckf::ROS2Visualizer::it_pub_tracks
image_transport::Publisher it_pub_tracks
Definition: ROS2Visualizer.h:148
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...)
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
REDPURPLE
#define REDPURPLE
ov_msckf::ROS2Visualizer::publish_groundtruth
void publish_groundtruth()
Publish groundtruth (if we have it)
Definition: ROS2Visualizer.cpp:706
sensor_data.h
ov_msckf::ROS2Visualizer::subs_cam
std::vector< rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr > subs_cam
Definition: ROS2Visualizer.h:160
ov_msckf::ROS2Visualizer::pub_posegt
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr pub_posegt
Definition: ROS2Visualizer.h:170
ov_core::CameraData
cv_bridge::Exception
ov_msckf::ROS2Visualizer::publish_state
void publish_state()
Publish the current state.
Definition: ROS2Visualizer.cpp:591
ov_msckf::ROS2Visualizer::of_state_est
std::ofstream of_state_est
Definition: ROS2Visualizer.h:208
PRINT_ERROR
#define PRINT_ERROR(x...)
StateHelper.h
f
f
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
ov_core::CameraData::sensor_ids
std::vector< int > sensor_ids
ov_msckf::ROS2Visualizer::_app
std::shared_ptr< VioManager > _app
Core application of the filter system.
Definition: ROS2Visualizer.h:142
ov_msckf::ROS2Visualizer::rT1
boost::posix_time::ptime rT1
Definition: ROS2Visualizer.h:179
ov_msckf::ROS2Visualizer::sync_subs_cam
std::vector< std::shared_ptr< message_filters::Subscriber< sensor_msgs::msg::Image > > > sync_subs_cam
Definition: ROS2Visualizer.h:163
ov_msckf::ROS2Visualizer::camera_queue
std::deque< ov_core::CameraData > camera_queue
Definition: ROS2Visualizer.h:188
ov_msckf::ROS2Visualizer::last_visualization_timestamp
double last_visualization_timestamp
Definition: ROS2Visualizer.h:195
ov_core::CameraData::timestamp
double timestamp
ov_msckf::ROS2Visualizer::pub_loop_point
rclcpp::Publisher< sensor_msgs::msg::PointCloud >::SharedPtr pub_loop_point
Definition: ROS2Visualizer.h:154
ov_core::CameraData::masks
std::vector< cv::Mat > masks
ROS2Visualizer.h
ov_msckf::ROS2Visualizer::summed_nees_ori
double summed_nees_ori
Definition: ROS2Visualizer.h:173
ov_msckf::ROS2Visualizer::setup_subscribers
void setup_subscribers(std::shared_ptr< ov_core::YamlParser > parser)
Will setup ROS subscribers and callbacks.
Definition: ROS2Visualizer.cpp:163
ov_msckf::ROS2Visualizer::_node
std::shared_ptr< rclcpp::Node > _node
Global node handler.
Definition: ROS2Visualizer.h:139
ov_msckf::ROS2Visualizer::save_total_state
bool save_total_state
Definition: ROS2Visualizer.h:207
ov_msckf::ROS2Visualizer::summed_mse_pos
double summed_mse_pos
Definition: ROS2Visualizer.h:172
VioManager.h
ov_msckf::ROS2Visualizer::it_pub_loop_img_depth_color
image_transport::Publisher it_pub_loop_img_depth_color
Definition: ROS2Visualizer.h:148
ov_msckf::StateHelper::get_marginal_covariance
static Eigen::MatrixXd get_marginal_covariance(std::shared_ptr< State > state, const std::vector< std::shared_ptr< ov_type::Type >> &small_variables)
For a given set of variables, this will this will calculate a smaller covariance.
Definition: StateHelper.cpp:226
BLUE
BLUE
ov_msckf::ROS2Visualizer::pub_pathgt
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr pub_pathgt
Definition: ROS2Visualizer.h:169
ov_msckf::ROS2Visualizer::pub_pathimu
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr pub_pathimu
Definition: ROS2Visualizer.h:151
ov_msckf::ROS2Visualizer::visualize_odometry
void visualize_odometry(double timestamp)
Will publish our odometry message for the current timestep. This will take the current state estimate...
Definition: ROS2Visualizer.cpp:269
ov_msckf::ROS2Visualizer::publish_images
void publish_images()
Publish the active tracking image.
Definition: ROS2Visualizer.cpp:646
ov_core::ImuData::wm
Eigen::Matrix< double, 3, 1 > wm
ov_msckf::ROS2Visualizer::visualize
void visualize()
Will visualize the system if we have new things.
Definition: ROS2Visualizer.cpp:221
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
ov_msckf::ROS2Visualizer::pub_points_aruco
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_aruco
Definition: ROS2Visualizer.h:152
app
app
ov_core::ImuData
ov_msckf::ROS2Visualizer::callback_stereo
void callback_stereo(const sensor_msgs::msg::Image::ConstSharedPtr msg0, const sensor_msgs::msg::Image::ConstSharedPtr msg1, int cam_id0, int cam_id1)
Callback for synchronized stereo camera information.
Definition: ROS2Visualizer.cpp:537
ov_msckf::ROS2Visualizer::publish_loopclosure_information
void publish_loopclosure_information()
Publish loop-closure information of current pose and active track information.
Definition: ROS2Visualizer.cpp:833
ov_msckf::ROS2Visualizer::callback_monocular
void callback_monocular(const sensor_msgs::msg::Image::SharedPtr msg0, int cam_id0)
Callback for monocular cameras information.
Definition: ROS2Visualizer.cpp:498
quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
ov_msckf::ROS2Visualizer::visualize_final
void visualize_final()
After the run has ended, print results.
Definition: ROS2Visualizer.cpp:352
ov_msckf::ROS2Visualizer::sync_cam
std::vector< std::shared_ptr< message_filters::Synchronizer< sync_pol > > > sync_cam
Definition: ROS2Visualizer.h:162
ov_msckf::ROS2Visualizer::pub_loop_pose
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_loop_pose
Definition: ROS2Visualizer.h:153
ov_core::ImuData::am
Eigen::Matrix< double, 3, 1 > am
ov_msckf::ROS2Visualizer::callback_inertial
void callback_inertial(const sensor_msgs::msg::Imu::SharedPtr msg)
Callback for inertial information.
Definition: ROS2Visualizer.cpp:438
ov_msckf::ROS2Visualizer::pub_poseimu
rclcpp::Publisher< geometry_msgs::msg::PoseWithCovarianceStamped >::SharedPtr pub_poseimu
Definition: ROS2Visualizer.h:149
print.h
ov_msckf::ROS2Visualizer::publish_global2imu_tf
bool publish_global2imu_tf
Definition: ROS2Visualizer.h:203
ov_msckf::ROS2Visualizer::summed_number
size_t summed_number
Definition: ROS2Visualizer.h:175
ov_msckf::State::Tg
static Eigen::Matrix3d Tg(const Eigen::MatrixXd &vec)
Gyroscope gravity sensitivity.
Definition: State.h:110
sensor_msgs::image_encodings::MONO8
const std::string MONO8
ov_msckf::ROS2Visualizer::mTfBr
std::shared_ptr< tf2_ros::TransformBroadcaster > mTfBr
Definition: ROS2Visualizer.h:156
PRINT_INFO
#define PRINT_INFO(x...)
ov_msckf::ROS2Visualizer::pub_points_slam
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_slam
Definition: ROS2Visualizer.h:152
ov_type
ov_msckf::ROS2Visualizer::gt_states
std::map< double, Eigen::Matrix< double, 17, 1 > > gt_states
Definition: ROS2Visualizer.h:199
RESET
#define RESET
cv_bridge::CvImage
dataset_reader.h
ov_msckf::ROS2Visualizer::pub_points_msckf
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_msckf
Definition: ROS2Visualizer.h:152
sim
std::shared_ptr< Simulator > sim
Definition: run_simulation.cpp:42
Inv
Eigen::Matrix< double, 4, 1 > Inv(Eigen::Matrix< double, 4, 1 > q)
ov_msckf::ROS2Visualizer::publish_features
void publish_features()
Publish current features.
Definition: ROS2Visualizer.cpp:674
ov_msckf::ROS2Visualizer::pub_odomimu
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_odomimu
Definition: ROS2Visualizer.h:150
State.h
ov_msckf::ROS2Visualizer::poses_gt
std::vector< geometry_msgs::msg::PoseStamped > poses_gt
Definition: ROS2Visualizer.h:202
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ov_msckf::ROS2Visualizer::rT2
boost::posix_time::ptime rT2
Definition: ROS2Visualizer.h:179
header
const std::string header
ov_core::ImuData::timestamp
double timestamp
Simulator.h
ov_msckf::ROSVisualizerHelper::sim_save_total_state_to_file
static void sim_save_total_state_to_file(std::shared_ptr< State > state, std::shared_ptr< Simulator > sim, std::ofstream &of_state_est, std::ofstream &of_state_std, std::ofstream &of_state_gt)
Save current estimate state and groundtruth including calibration.
Definition: ROSVisualizerHelper.cpp:154
ov_msckf::ROS2Visualizer::pub_loop_intrinsics
rclcpp::Publisher< sensor_msgs::msg::CameraInfo >::SharedPtr pub_loop_intrinsics
Definition: ROS2Visualizer.h:155
ov_msckf::ROS2Visualizer::pub_loop_extrinsic
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_loop_extrinsic
Definition: ROS2Visualizer.h:153
ov_msckf::ROS2Visualizer::of_state_std
std::ofstream of_state_std
Definition: ROS2Visualizer.h:208
ov_msckf::ROS2Visualizer::sub_imu
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr sub_imu
Definition: ROS2Visualizer.h:159
ov_msckf::ROS2Visualizer::summed_mse_ori
double summed_mse_ori
Definition: ROS2Visualizer.h:171
ov_core
ov_msckf::ROS2Visualizer::pub_points_sim
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_sim
Definition: ROS2Visualizer.h:152
ov_msckf::ROS2Visualizer::last_visualization_timestamp_image
double last_visualization_timestamp_image
Definition: ROS2Visualizer.h:196
ov_msckf::ROS2Visualizer::start_time_set
bool start_time_set
Definition: ROS2Visualizer.h:178


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