22 #ifndef OV_MSCKF_ROSVISUALIZER_HELPER_H
23 #define OV_MSCKF_ROSVISUALIZER_HELPER_H
25 #include <Eigen/Eigen>
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>
56 #if ROS_AVAILABLE == 1
62 static sensor_msgs::PointCloud2 get_ros_pointcloud(
const std::vector<Eigen::Vector3d> &feats);
73 static tf::StampedTransform get_stamped_transform_from_pose(
const std::shared_ptr<ov_type::PoseJPL> &pose,
bool flip_trans);
76 #if ROS_AVAILABLE == 2
83 static sensor_msgs::msg::PointCloud2 get_ros_pointcloud(std::shared_ptr<rclcpp::Node> node,
const std::vector<Eigen::Vector3d> &feats);
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);
103 static rclcpp::Time get_time_from_seconds(
double seconds) {
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));
115 sec += (nsec / 1000000000ul);
116 nsec %= 1000000000ul;
117 return rclcpp::Time(sec, nsec);
131 std::ofstream &of_state_std, std::ofstream &of_state_gt);
140 #endif // OV_MSCKF_ROSVISUALIZER_HELPER_H