|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
20 #define LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
24 #include <ff_msgs/DepthOdometry.h>
25 #include <ff_msgs/Feature2dArray.h>
26 #include <ff_msgs/FlightMode.h>
27 #include <ff_msgs/VisualLandmarks.h>
36 #include <rosbag/view.h>
37 #include <sensor_msgs/Image.h>
38 #include <sensor_msgs/Imu.h>
64 ff_msgs::Feature2dArray GenerateOFFeatures(
const sensor_msgs::ImageConstPtr& image_msg);
66 bool GenerateVLFeatures(
const sensor_msgs::ImageConstPtr& image_msg, ff_msgs::VisualLandmarks& vl_features);
74 const std::string kImageTopic_;
75 std::string topic_localization_depth_image_;
76 std::string topic_localization_depth_cloud_;
77 std::unique_ptr<rosbag::View> view_;
78 boost::optional<rosbag::View::iterator> view_it_;
79 std::map<localization_common::Time, sensor_msgs::ImageConstPtr> img_buffer_;
90 #endif // LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
Definition: live_measurement_simulator.h:47
localization_common::Time CurrentTime()
Definition: live_measurement_simulator.cc:171
bool ProcessMessage()
Definition: live_measurement_simulator.cc:113
Definition: ar_tag_pose_adder.h:29
Definition: live_measurement_simulator_params.h:26
Definition: localization.h:45
Definition: depth_odometry_wrapper.h:39
boost::optional< ff_msgs::DepthOdometry > GetDepthOdometryMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:182
boost::optional< ff_msgs::VisualLandmarks > GetARMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:188
boost::optional< ff_msgs::Feature2dArray > GetOFMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:179
LiveMeasurementSimulator(const LiveMeasurementSimulatorParams ¶ms)
Definition: live_measurement_simulator.cc:29
boost::optional< ff_msgs::FlightMode > GetFlightModeMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:176
boost::optional< sensor_msgs::Imu > GetImuMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:173
Definition: sparse_map.h:63
double Time
Definition: time.h:23
boost::optional< ff_msgs::VisualLandmarks > GetVLMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:185
boost::optional< sensor_msgs::ImageConstPtr > GetImageMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:191
Definition: lk_optical_flow.h:36