48 const std::string &msceqf_config_filepath,
49 const std::string &imu_topic,
50 const std::string &cam_topic,
51 const std::string &pose_topic,
52 const std::string &path_topic,
53 const std::string &image_topic,
54 const std::string &extrinsics_topic,
55 const std::string &intrinsics_topic,
56 const std::string &origin_topic,
58 const std::string &bagfile);
84 ros::Subscriber sub_cam_;
85 ros::Subscriber sub_imu_;
87 ros::Publisher pub_pose_;
88 ros::Publisher pub_image_;
89 ros::Publisher pub_path_;
90 ros::Publisher pub_extrinsics_;
91 ros::Publisher pub_intrinsics_;
92 ros::Publisher pub_origin_;
94 geometry_msgs::PoseWithCovarianceStamped pose_;
96 geometry_msgs::PoseStamped extrinsics_;
97 sensor_msgs::CameraInfo intrinsics_;
98 geometry_msgs::PoseStamped origin_;
100 std::deque<msceqf::Camera> cams_;
102 std::atomic<bool> processing_ =
false;
MSCEqFRos(const ros::NodeHandle &nh, const std::string &msceqf_config_filepath, const std::string &imu_topic, const std::string &cam_topic, const std::string &pose_topic, const std::string &path_topic, const std::string &image_topic, const std::string &extrinsics_topic, const std::string &intrinsics_topic, const std::string &origin_topic, const bool &record, const std::string &bagfile)
Constructor.