ROS1Visualizer.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_ROS1VISUALIZER_H
23 #define OV_MSCKF_ROS1VISUALIZER_H
24 
25 #include <geometry_msgs/PoseStamped.h>
26 #include <geometry_msgs/PoseWithCovarianceStamped.h>
31 #include <nav_msgs/Odometry.h>
32 #include <nav_msgs/Path.h>
33 #include <ros/ros.h>
34 #include <sensor_msgs/CameraInfo.h>
35 #include <sensor_msgs/Image.h>
36 #include <sensor_msgs/Imu.h>
37 #include <sensor_msgs/NavSatFix.h>
38 #include <sensor_msgs/PointCloud.h>
39 #include <sensor_msgs/PointCloud2.h>
41 #include <std_msgs/Float64.h>
43 
44 #include <atomic>
45 #include <fstream>
46 #include <memory>
47 #include <mutex>
48 
49 #include <Eigen/Eigen>
50 #include <boost/date_time/posix_time/posix_time.hpp>
51 #include <boost/filesystem.hpp>
52 #include <cv_bridge/cv_bridge.h>
53 
54 namespace ov_core {
55 class YamlParser;
56 struct CameraData;
57 } // namespace ov_core
58 
59 namespace ov_msckf {
60 
61 class VioManager;
62 class Simulator;
63 
75 
76 public:
83  ROS1Visualizer(std::shared_ptr<ros::NodeHandle> nh, std::shared_ptr<VioManager> app, std::shared_ptr<Simulator> sim = nullptr);
84 
89  void setup_subscribers(std::shared_ptr<ov_core::YamlParser> parser);
90 
94  void visualize();
95 
101  void visualize_odometry(double timestamp);
102 
106  void visualize_final();
107 
109  void callback_inertial(const sensor_msgs::Imu::ConstPtr &msg);
110 
112  void callback_monocular(const sensor_msgs::ImageConstPtr &msg0, int cam_id0);
113 
115  void callback_stereo(const sensor_msgs::ImageConstPtr &msg0, const sensor_msgs::ImageConstPtr &msg1, int cam_id0, int cam_id1);
116 
117 protected:
119  void publish_state();
120 
122  void publish_images();
123 
125  void publish_features();
126 
128  void publish_groundtruth();
129 
132 
134  std::shared_ptr<ros::NodeHandle> _nh;
135 
137  std::shared_ptr<VioManager> _app;
138 
140  std::shared_ptr<Simulator> _sim;
141 
142  // Our publishers
147  std::shared_ptr<tf::TransformBroadcaster> mTfBr;
148 
149  // Our subscribers and camera synchronizers
151  std::vector<ros::Subscriber> subs_cam;
153  std::vector<std::shared_ptr<message_filters::Synchronizer<sync_pol>>> sync_cam;
154  std::vector<std::shared_ptr<message_filters::Subscriber<sensor_msgs::Image>>> sync_subs_cam;
155 
156  // For path viz
157  unsigned int poses_seq_imu = 0;
158  std::vector<geometry_msgs::PoseStamped> poses_imu;
159 
160  // Groundtruth infomation
162  double summed_mse_ori = 0.0;
163  double summed_mse_pos = 0.0;
164  double summed_nees_ori = 0.0;
165  double summed_nees_pos = 0.0;
166  size_t summed_number = 0;
167 
168  // Start and end timestamps
169  bool start_time_set = false;
170  boost::posix_time::ptime rT1, rT2;
171 
172  // Thread atomics
173  std::atomic<bool> thread_update_running;
174 
179  std::deque<ov_core::CameraData> camera_queue;
180  std::mutex camera_queue_mtx;
181 
182  // Last camera message timestamps we have received (mapped by cam id)
183  std::map<int, double> camera_last_timestamp;
184 
185  // Last timestamp we visualized at
188 
189  // Our groundtruth states
190  std::map<double, Eigen::Matrix<double, 17, 1>> gt_states;
191 
192  // For path viz
193  unsigned int poses_seq_gt = 0;
194  std::vector<geometry_msgs::PoseStamped> poses_gt;
197 
198  // Files and if we should save total state
199  bool save_total_state = false;
201 };
202 
203 } // namespace ov_msckf
204 
205 #endif // OV_MSCKF_ROS1VISUALIZER_H
ov_msckf::ROS1Visualizer::sync_pol
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > sync_pol
Definition: ROS1Visualizer.h:152
ov_msckf::ROS1Visualizer::camera_queue_mtx
std::mutex camera_queue_mtx
Definition: ROS1Visualizer.h:180
ov_msckf::ROS1Visualizer::summed_mse_pos
double summed_mse_pos
Definition: ROS1Visualizer.h:163
ov_msckf::ROS1Visualizer::rT2
boost::posix_time::ptime rT2
Definition: ROS1Visualizer.h:170
ov_msckf::ROS1Visualizer::_app
std::shared_ptr< VioManager > _app
Core application of the filter system.
Definition: ROS1Visualizer.h:137
point_cloud2_iterator.h
ov_msckf::ROS1Visualizer::poses_gt
std::vector< geometry_msgs::PoseStamped > poses_gt
Definition: ROS1Visualizer.h:194
ov_msckf::ROS1Visualizer::pub_posegt
ros::Publisher pub_posegt
Definition: ROS1Visualizer.h:161
ov_msckf::ROS1Visualizer::pub_points_msckf
ros::Publisher pub_points_msckf
Definition: ROS1Visualizer.h:145
ros::Publisher
ov_msckf::ROS1Visualizer::publish_groundtruth
void publish_groundtruth()
Publish groundtruth (if we have it)
Definition: ROS1Visualizer.cpp:711
ov_msckf::ROS1Visualizer::rT1
boost::posix_time::ptime rT1
Definition: ROS1Visualizer.h:170
ov_msckf::ROS1Visualizer::publish_features
void publish_features()
Publish current features.
Definition: ROS1Visualizer.cpp:679
ros.h
ov_msckf::ROS1Visualizer::poses_seq_gt
unsigned int poses_seq_gt
Definition: ROS1Visualizer.h:193
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::ROS1Visualizer::summed_number
size_t summed_number
Definition: ROS1Visualizer.h:166
ov_msckf::ROS1Visualizer::_sim
std::shared_ptr< Simulator > _sim
Simulator (is nullptr if we are not sim'ing)
Definition: ROS1Visualizer.h:140
ov_msckf::ROS1Visualizer::poses_imu
std::vector< geometry_msgs::PoseStamped > poses_imu
Definition: ROS1Visualizer.h:158
time_synchronizer.h
ov_msckf::ROS1Visualizer::_nh
std::shared_ptr< ros::NodeHandle > _nh
Global node handler.
Definition: ROS1Visualizer.h:134
ov_msckf::ROS1Visualizer::last_visualization_timestamp_image
double last_visualization_timestamp_image
Definition: ROS1Visualizer.h:187
ov_msckf::ROS1Visualizer::pub_pathimu
ros::Publisher pub_pathimu
Definition: ROS1Visualizer.h:144
ov_msckf::ROS1Visualizer::poses_seq_imu
unsigned int poses_seq_imu
Definition: ROS1Visualizer.h:157
ov_msckf::ROS1Visualizer::publish_loopclosure_information
void publish_loopclosure_information()
Publish loop-closure information of current pose and active track information.
Definition: ROS1Visualizer.cpp:840
ov_msckf::ROS1Visualizer::pub_odomimu
ros::Publisher pub_odomimu
Definition: ROS1Visualizer.h:144
ov_msckf::ROS1Visualizer::it_pub_loop_img_depth
image_transport::Publisher it_pub_loop_img_depth
Definition: ROS1Visualizer.h:143
ov_msckf::ROS1Visualizer::callback_inertial
void callback_inertial(const sensor_msgs::Imu::ConstPtr &msg)
Callback for inertial information.
Definition: ROS1Visualizer.cpp:438
transform_broadcaster.h
ov_msckf::ROS1Visualizer::it_pub_tracks
image_transport::Publisher it_pub_tracks
Definition: ROS1Visualizer.h:143
ov_msckf::ROS1Visualizer::pub_pathgt
ros::Publisher pub_pathgt
Definition: ROS1Visualizer.h:161
ov_msckf::ROS1Visualizer::sub_imu
ros::Subscriber sub_imu
Definition: ROS1Visualizer.h:150
ov_msckf::ROS1Visualizer::pub_points_slam
ros::Publisher pub_points_slam
Definition: ROS1Visualizer.h:145
ov_msckf::ROS1Visualizer::visualize
void visualize()
Will visualize the system if we have new things.
Definition: ROS1Visualizer.cpp:197
ov_msckf::ROS1Visualizer::thread_update_running
std::atomic< bool > thread_update_running
Definition: ROS1Visualizer.h:173
ov_msckf::ROS1Visualizer::publish_calibration_tf
bool publish_calibration_tf
Definition: ROS1Visualizer.h:196
ov_msckf::ROS1Visualizer::publish_state
void publish_state()
Publish the current state.
Definition: ROS1Visualizer.cpp:591
ov_msckf::ROS1Visualizer::sync_cam
std::vector< std::shared_ptr< message_filters::Synchronizer< sync_pol > > > sync_cam
Definition: ROS1Visualizer.h:153
message_filters::sync_policies::ApproximateTime
ov_msckf::ROS1Visualizer::publish_images
void publish_images()
Publish the active tracking image.
Definition: ROS1Visualizer.cpp:651
subscriber.h
ov_msckf::ROS1Visualizer::last_visualization_timestamp
double last_visualization_timestamp
Definition: ROS1Visualizer.h:186
ov_msckf::ROS1Visualizer::camera_queue
std::deque< ov_core::CameraData > camera_queue
Definition: ROS1Visualizer.h:179
ov_msckf::ROS1Visualizer::sync_subs_cam
std::vector< std::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > sync_subs_cam
Definition: ROS1Visualizer.h:154
ov_msckf::ROS1Visualizer::subs_cam
std::vector< ros::Subscriber > subs_cam
Definition: ROS1Visualizer.h:151
app
app
ov_msckf::ROS1Visualizer::pub_loop_point
ros::Publisher pub_loop_point
Definition: ROS1Visualizer.h:146
ov_msckf::ROS1Visualizer::visualize_odometry
void visualize_odometry(double timestamp)
Will publish our odometry message for the current timestep. This will take the current state estimate...
Definition: ROS1Visualizer.cpp:245
image_transport.h
ov_msckf::ROS1Visualizer::pub_loop_pose
ros::Publisher pub_loop_pose
Definition: ROS1Visualizer.h:146
ov_msckf::ROS1Visualizer::it_pub_loop_img_depth_color
image_transport::Publisher it_pub_loop_img_depth_color
Definition: ROS1Visualizer.h:143
ov_msckf::ROS1Visualizer::pub_points_sim
ros::Publisher pub_points_sim
Definition: ROS1Visualizer.h:145
ov_msckf::ROS1Visualizer::summed_nees_pos
double summed_nees_pos
Definition: ROS1Visualizer.h:165
image_transport::Publisher
ov_msckf::ROS1Visualizer::callback_monocular
void callback_monocular(const sensor_msgs::ImageConstPtr &msg0, int cam_id0)
Callback for monocular cameras information.
Definition: ROS1Visualizer.cpp:498
ov_msckf::ROS1Visualizer::pub_poseimu
ros::Publisher pub_poseimu
Definition: ROS1Visualizer.h:144
cv_bridge.h
ov_msckf::ROS1Visualizer::camera_last_timestamp
std::map< int, double > camera_last_timestamp
Definition: ROS1Visualizer.h:183
ov_msckf::ROS1Visualizer::summed_nees_ori
double summed_nees_ori
Definition: ROS1Visualizer.h:164
sim
std::shared_ptr< Simulator > sim
Definition: run_simulation.cpp:42
ov_msckf::ROS1Visualizer::publish_global2imu_tf
bool publish_global2imu_tf
Definition: ROS1Visualizer.h:195
ov_msckf::ROS1Visualizer::mTfBr
std::shared_ptr< tf::TransformBroadcaster > mTfBr
Definition: ROS1Visualizer.h:147
ov_msckf::ROS1Visualizer::pub_points_aruco
ros::Publisher pub_points_aruco
Definition: ROS1Visualizer.h:145
ov_msckf::ROS1Visualizer::callback_stereo
void callback_stereo(const sensor_msgs::ImageConstPtr &msg0, const sensor_msgs::ImageConstPtr &msg1, int cam_id0, int cam_id1)
Callback for synchronized stereo camera information.
Definition: ROS1Visualizer.cpp:537
approximate_time.h
ov_msckf::ROS1Visualizer::visualize_final
void visualize_final()
After the run has ended, print results.
Definition: ROS1Visualizer.cpp:352
ov_msckf::ROS1Visualizer::of_state_est
std::ofstream of_state_est
Definition: ROS1Visualizer.h:200
ov_msckf::ROS1Visualizer::ROS1Visualizer
ROS1Visualizer(std::shared_ptr< ros::NodeHandle > nh, std::shared_ptr< VioManager > app, std::shared_ptr< Simulator > sim=nullptr)
Default constructor.
Definition: ROS1Visualizer.cpp:38
ov_msckf::ROS1Visualizer::setup_subscribers
void setup_subscribers(std::shared_ptr< ov_core::YamlParser > parser)
Will setup ROS subscribers and callbacks.
Definition: ROS1Visualizer.cpp:151
ov_msckf::ROS1Visualizer
Helper class that will publish results onto the ROS framework.
Definition: ROS1Visualizer.h:74
ov_msckf::ROS1Visualizer::pub_loop_intrinsics
ros::Publisher pub_loop_intrinsics
Definition: ROS1Visualizer.h:146
ov_msckf::ROS1Visualizer::gt_states
std::map< double, Eigen::Matrix< double, 17, 1 > > gt_states
Definition: ROS1Visualizer.h:190
ov_msckf::ROS1Visualizer::pub_loop_extrinsic
ros::Publisher pub_loop_extrinsic
Definition: ROS1Visualizer.h:146
ov_msckf::ROS1Visualizer::start_time_set
bool start_time_set
Definition: ROS1Visualizer.h:169
ov_core
ov_msckf::ROS1Visualizer::save_total_state
bool save_total_state
Definition: ROS1Visualizer.h:199
ros::Subscriber
ov_msckf::ROS1Visualizer::of_state_std
std::ofstream of_state_std
Definition: ROS1Visualizer.h:200
ov_msckf::ROS1Visualizer::of_state_gt
std::ofstream of_state_gt
Definition: ROS1Visualizer.h:200
ov_msckf::ROS1Visualizer::summed_mse_ori
double summed_mse_ori
Definition: ROS1Visualizer.h:162


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