ROSVisualizerHelper.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_ROSVISUALIZER_HELPER_H
23 #define OV_MSCKF_ROSVISUALIZER_HELPER_H
24 
25 #include <Eigen/Eigen>
26 
27 #if ROS_AVAILABLE == 1
28 #include <sensor_msgs/PointCloud.h>
29 #include <sensor_msgs/PointCloud2.h>
32 #elif ROS_AVAILABLE == 2
33 #include <sensor_msgs/msg/point_cloud.hpp>
34 #include <sensor_msgs/msg/point_cloud2.hpp>
35 #include <sensor_msgs/point_cloud2_iterator.hpp>
37 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
38 #endif
39 
40 namespace ov_type {
41 class PoseJPL;
42 }
43 
44 namespace ov_msckf {
45 
46 class State;
47 class VioManager;
48 class Simulator;
49 
54 
55 public:
56 #if ROS_AVAILABLE == 1
57 
62  static sensor_msgs::PointCloud2 get_ros_pointcloud(const std::vector<Eigen::Vector3d> &feats);
63 
73  static tf::StampedTransform get_stamped_transform_from_pose(const std::shared_ptr<ov_type::PoseJPL> &pose, bool flip_trans);
74 #endif
75 
76 #if ROS_AVAILABLE == 2
77 
83  static sensor_msgs::msg::PointCloud2 get_ros_pointcloud(std::shared_ptr<rclcpp::Node> node, const std::vector<Eigen::Vector3d> &feats);
84 
95  static geometry_msgs::msg::TransformStamped
96  get_stamped_transform_from_pose(std::shared_ptr<rclcpp::Node> node, const std::shared_ptr<ov_type::PoseJPL> &pose, bool flip_trans);
97 
103  static rclcpp::Time get_time_from_seconds(double seconds) {
104 
105  // ROS2 time class has no double constructor
106  // Extract compatible time from timestamp using ros1 implementation for now
107  uint32_t sec, nsec;
108  int64_t sec64 = static_cast<int64_t>(floor(seconds));
109  if (sec64 < 0 || sec64 > std::numeric_limits<uint32_t>::max())
110  throw std::runtime_error("Time is out of dual 32-bit range");
111  sec = static_cast<uint32_t>(sec64);
112  nsec = static_cast<uint32_t>(std::round((seconds - sec) * 1e9));
113 
114  // Avoid rounding errors
115  sec += (nsec / 1000000000ul);
116  nsec %= 1000000000ul;
117  return rclcpp::Time(sec, nsec);
118  }
119 
120 #endif
121 
130  static void sim_save_total_state_to_file(std::shared_ptr<State> state, std::shared_ptr<Simulator> sim, std::ofstream &of_state_est,
131  std::ofstream &of_state_std, std::ofstream &of_state_gt);
132 
133 private:
134  // Cannot create this class
135  ROSVisualizerHelper() = default;
136 };
137 
138 } // namespace ov_msckf
139 
140 #endif // OV_MSCKF_ROSVISUALIZER_HELPER_H
ov_msckf::ROSVisualizerHelper
Helper class that handles some common versions into and out of ROS formats.
Definition: ROSVisualizerHelper.h:53
point_cloud2_iterator.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
tf::StampedTransform
transform_broadcaster.h
ov_msckf::ROSVisualizerHelper::ROSVisualizerHelper
ROSVisualizerHelper()=default
transform_datatypes.h
ov_type
sim
std::shared_ptr< Simulator > sim
Definition: run_simulation.cpp:42
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
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54