ROS2Visualizer.h
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 #ifndef OV_MSCKF_ROS2VISUALIZER_H
23 #define OV_MSCKF_ROS2VISUALIZER_H
24 
25 #include <geometry_msgs/msg/pose_stamped.hpp>
26 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
27 #include <geometry_msgs/msg/transform_stamped.hpp>
32 #include <nav_msgs/msg/odometry.hpp>
33 #include <nav_msgs/msg/path.hpp>
34 #include <rclcpp/rclcpp.hpp>
35 #include <sensor_msgs/msg/camera_info.hpp>
36 #include <sensor_msgs/msg/image.hpp>
37 #include <sensor_msgs/msg/imu.hpp>
38 #include <sensor_msgs/msg/nav_sat_fix.hpp>
39 #include <sensor_msgs/msg/point_cloud.hpp>
40 #include <sensor_msgs/msg/point_cloud2.hpp>
41 #include <sensor_msgs/point_cloud2_iterator.hpp>
42 #include <std_msgs/msg/float64.hpp>
45 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
47 
48 #include <atomic>
49 #include <fstream>
50 #include <memory>
51 #include <mutex>
52 
53 #include <Eigen/Eigen>
54 #include <boost/date_time/posix_time/posix_time.hpp>
55 #include <boost/filesystem.hpp>
56 #include <cv_bridge/cv_bridge.h>
57 
58 namespace ov_core {
59 class YamlParser;
60 struct CameraData;
61 } // namespace ov_core
62 
63 namespace ov_msckf {
64 
65 class VioManager;
66 class Simulator;
67 
79 
80 public:
87  ROS2Visualizer(std::shared_ptr<rclcpp::Node> node, std::shared_ptr<VioManager> app, std::shared_ptr<Simulator> sim = nullptr);
88 
93  void setup_subscribers(std::shared_ptr<ov_core::YamlParser> parser);
94 
98  void visualize();
99 
105  void visualize_odometry(double timestamp);
106 
110  void visualize_final();
111 
113  void callback_inertial(const sensor_msgs::msg::Imu::SharedPtr msg);
114 
116  void callback_monocular(const sensor_msgs::msg::Image::SharedPtr msg0, int cam_id0);
117 
119  void callback_stereo(const sensor_msgs::msg::Image::ConstSharedPtr msg0, const sensor_msgs::msg::Image::ConstSharedPtr msg1, int cam_id0,
120  int cam_id1);
121 
122 protected:
124  void publish_state();
125 
127  void publish_images();
128 
130  void publish_features();
131 
133  void publish_groundtruth();
134 
137 
139  std::shared_ptr<rclcpp::Node> _node;
140 
142  std::shared_ptr<VioManager> _app;
143 
145  std::shared_ptr<Simulator> _sim;
146 
147  // Our publishers
149  rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pub_poseimu;
150  rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odomimu;
151  rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr pub_pathimu;
152  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_points_msckf, pub_points_slam, pub_points_aruco, pub_points_sim;
153  rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_loop_pose, pub_loop_extrinsic;
154  rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr pub_loop_point;
155  rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr pub_loop_intrinsics;
156  std::shared_ptr<tf2_ros::TransformBroadcaster> mTfBr;
157 
158  // Our subscribers and camera synchronizers
159  rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr sub_imu;
160  std::vector<rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr> subs_cam;
162  std::vector<std::shared_ptr<message_filters::Synchronizer<sync_pol>>> sync_cam;
163  std::vector<std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::Image>>> sync_subs_cam;
164 
165  // For path viz
166  std::vector<geometry_msgs::msg::PoseStamped> poses_imu;
167 
168  // Groundtruth infomation
169  rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr pub_pathgt;
170  rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_posegt;
171  double summed_mse_ori = 0.0;
172  double summed_mse_pos = 0.0;
173  double summed_nees_ori = 0.0;
174  double summed_nees_pos = 0.0;
175  size_t summed_number = 0;
176 
177  // Start and end timestamps
178  bool start_time_set = false;
179  boost::posix_time::ptime rT1, rT2;
180 
181  // Thread atomics
182  std::atomic<bool> thread_update_running;
183 
188  std::deque<ov_core::CameraData> camera_queue;
189  std::mutex camera_queue_mtx;
190 
191  // Last camera message timestamps we have received (mapped by cam id)
192  std::map<int, double> camera_last_timestamp;
193 
194  // Last timestamp we visualized at
197 
198  // Our groundtruth states
199  std::map<double, Eigen::Matrix<double, 17, 1>> gt_states;
200 
201  // For path viz
202  std::vector<geometry_msgs::msg::PoseStamped> poses_gt;
205 
206  // Files and if we should save total state
207  bool save_total_state = false;
209 };
210 
211 } // namespace ov_msckf
212 
213 #endif // OV_MSCKF_ROS2VISUALIZER_H
ov_msckf::ROS2Visualizer::publish_calibration_tf
bool publish_calibration_tf
Definition: ROS2Visualizer.h:204
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
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
ov_msckf::ROS2Visualizer::thread_update_running
std::atomic< bool > thread_update_running
Definition: ROS2Visualizer.h:182
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
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
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::ROS2Visualizer::publish_groundtruth
void publish_groundtruth()
Publish groundtruth (if we have it)
Definition: ROS2Visualizer.cpp:706
ov_msckf::ROS2Visualizer::subs_cam
std::vector< rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr > subs_cam
Definition: ROS2Visualizer.h:160
time_synchronizer.h
ov_msckf::ROS2Visualizer::pub_posegt
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr pub_posegt
Definition: ROS2Visualizer.h:170
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
transform_broadcaster.h
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
message_filters::sync_policies::ApproximateTime
ov_msckf::ROS2Visualizer::pub_loop_point
rclcpp::Publisher< sensor_msgs::msg::PointCloud >::SharedPtr pub_loop_point
Definition: ROS2Visualizer.h:154
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
Helper class that will publish results onto the ROS framework.
Definition: ROS2Visualizer.h:78
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
subscriber.h
Quaternion.h
ov_msckf::ROS2Visualizer::summed_mse_pos
double summed_mse_pos
Definition: ROS2Visualizer.h:172
ov_msckf::ROS2Visualizer::it_pub_loop_img_depth_color
image_transport::Publisher it_pub_loop_img_depth_color
Definition: ROS2Visualizer.h:148
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_msckf::ROS2Visualizer::visualize
void visualize()
Will visualize the system if we have new things.
Definition: ROS2Visualizer.cpp:221
ov_msckf::ROS2Visualizer::pub_points_aruco
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_aruco
Definition: ROS2Visualizer.h:152
app
app
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
ov_msckf::ROS2Visualizer::visualize_final
void visualize_final()
After the run has ended, print results.
Definition: ROS2Visualizer.cpp:352
image_transport.h
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_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
transform_datatypes.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
image_transport::Publisher
ov_msckf::ROS2Visualizer::mTfBr
std::shared_ptr< tf2_ros::TransformBroadcaster > mTfBr
Definition: ROS2Visualizer.h:156
ov_msckf::ROS2Visualizer::pub_points_slam
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_slam
Definition: ROS2Visualizer.h:152
cv_bridge.h
ov_msckf::ROS2Visualizer::gt_states
std::map< double, Eigen::Matrix< double, 17, 1 > > gt_states
Definition: ROS2Visualizer.h:199
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
approximate_time.h
ov_msckf::ROS2Visualizer::ROS2Visualizer
ROS2Visualizer(std::shared_ptr< rclcpp::Node > node, std::shared_ptr< VioManager > app, std::shared_ptr< Simulator > sim=nullptr)
Default constructor.
Definition: ROS2Visualizer.cpp:38
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
ov_msckf::ROS2Visualizer::poses_gt
std::vector< geometry_msgs::msg::PoseStamped > poses_gt
Definition: ROS2Visualizer.h:202
ov_msckf::ROS2Visualizer::rT2
boost::posix_time::ptime rT2
Definition: ROS2Visualizer.h:179
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