Go to the documentation of this file.
22 #ifndef OV_MSCKF_ROS2VISUALIZER_H
23 #define OV_MSCKF_ROS2VISUALIZER_H
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>
53 #include <Eigen/Eigen>
54 #include <boost/date_time/posix_time/posix_time.hpp>
55 #include <boost/filesystem.hpp>
87 ROS2Visualizer(std::shared_ptr<rclcpp::Node> node, std::shared_ptr<VioManager>
app, std::shared_ptr<Simulator>
sim =
nullptr);
119 void callback_stereo(
const sensor_msgs::msg::Image::ConstSharedPtr msg0,
const sensor_msgs::msg::Image::ConstSharedPtr msg1,
int cam_id0,
139 std::shared_ptr<rclcpp::Node>
_node;
142 std::shared_ptr<VioManager>
_app;
145 std::shared_ptr<Simulator>
_sim;
149 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
pub_poseimu;
150 rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr
pub_odomimu;
156 std::shared_ptr<tf2_ros::TransformBroadcaster>
mTfBr;
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;
169 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr
pub_pathgt;
170 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr
pub_posegt;
199 std::map<double, Eigen::Matrix<double, 17, 1>>
gt_states;
202 std::vector<geometry_msgs::msg::PoseStamped>
poses_gt;
213 #endif // OV_MSCKF_ROS2VISUALIZER_H
bool publish_calibration_tf
std::ofstream of_state_gt
std::shared_ptr< Simulator > _sim
Simulator (is nullptr if we are not sim'ing)
message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image > sync_pol
std::mutex camera_queue_mtx
std::atomic< bool > thread_update_running
std::vector< geometry_msgs::msg::PoseStamped > poses_imu
std::map< int, double > camera_last_timestamp
image_transport::Publisher it_pub_loop_img_depth
image_transport::Publisher it_pub_tracks
Extended Kalman Filter estimator.
void publish_groundtruth()
Publish groundtruth (if we have it)
std::vector< rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr > subs_cam
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr pub_posegt
void publish_state()
Publish the current state.
std::ofstream of_state_est
std::shared_ptr< VioManager > _app
Core application of the filter system.
boost::posix_time::ptime rT1
std::vector< std::shared_ptr< message_filters::Subscriber< sensor_msgs::msg::Image > > > sync_subs_cam
std::deque< ov_core::CameraData > camera_queue
double last_visualization_timestamp
rclcpp::Publisher< sensor_msgs::msg::PointCloud >::SharedPtr pub_loop_point
void setup_subscribers(std::shared_ptr< ov_core::YamlParser > parser)
Will setup ROS subscribers and callbacks.
Helper class that will publish results onto the ROS framework.
std::shared_ptr< rclcpp::Node > _node
Global node handler.
image_transport::Publisher it_pub_loop_img_depth_color
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr pub_pathgt
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr pub_pathimu
void visualize_odometry(double timestamp)
Will publish our odometry message for the current timestep. This will take the current state estimate...
void publish_images()
Publish the active tracking image.
void visualize()
Will visualize the system if we have new things.
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_aruco
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.
void publish_loopclosure_information()
Publish loop-closure information of current pose and active track information.
void callback_monocular(const sensor_msgs::msg::Image::SharedPtr msg0, int cam_id0)
Callback for monocular cameras information.
void visualize_final()
After the run has ended, print results.
std::vector< std::shared_ptr< message_filters::Synchronizer< sync_pol > > > sync_cam
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_loop_pose
void callback_inertial(const sensor_msgs::msg::Imu::SharedPtr msg)
Callback for inertial information.
rclcpp::Publisher< geometry_msgs::msg::PoseWithCovarianceStamped >::SharedPtr pub_poseimu
bool publish_global2imu_tf
std::shared_ptr< tf2_ros::TransformBroadcaster > mTfBr
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_slam
std::map< double, Eigen::Matrix< double, 17, 1 > > gt_states
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_msckf
std::shared_ptr< Simulator > sim
ROS2Visualizer(std::shared_ptr< rclcpp::Node > node, std::shared_ptr< VioManager > app, std::shared_ptr< Simulator > sim=nullptr)
Default constructor.
void publish_features()
Publish current features.
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_odomimu
std::vector< geometry_msgs::msg::PoseStamped > poses_gt
boost::posix_time::ptime rT2
rclcpp::Publisher< sensor_msgs::msg::CameraInfo >::SharedPtr pub_loop_intrinsics
rclcpp::Publisher< nav_msgs::msg::Odometry >::SharedPtr pub_loop_extrinsic
std::ofstream of_state_std
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr sub_imu
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_points_sim
double last_visualization_timestamp_image
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54