|
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_GRAPH_VIO_SIMULATOR_H_
20 #define LOCALIZATION_ANALYSIS_GRAPH_VIO_SIMULATOR_H_
22 #include <ff_msgs/Feature2dArray.h>
23 #include <ff_msgs/FlightMode.h>
24 #include <ff_msgs/VisualLandmarks.h>
29 #include <sensor_msgs/Image.h>
30 #include <sensor_msgs/Imu.h>
31 #include <sensor_msgs/PointCloud2.h>
55 std::vector<ff_msgs::Feature2dArray> of_msg_buffer_;
56 std::vector<ff_msgs::DepthOdometry> depth_odometry_msg_buffer_;
57 std::vector<sensor_msgs::Imu> imu_msg_buffer_;
58 std::vector<ff_msgs::FlightMode> flight_mode_msg_buffer_;
59 boost::optional<localization_common::Time> last_update_time_;
64 #endif // LOCALIZATION_ANALYSIS_GRAPH_VIO_SIMULATOR_H_
GraphVIOSimulator(const GraphVIOSimulatorParams ¶ms, const std::string &graph_config_path_prefix)
Definition: graph_vio_simulator.cc:23
void BufferDepthOdometryMsg(const ff_msgs::DepthOdometry &depth_odometry_msg)
Definition: graph_vio_simulator.cc:30
Definition: graph_vio_simulator.h:40
Definition: ar_tag_pose_adder.h:29
Definition: ros_graph_vio_wrapper.h:41
void BufferFlightModeMsg(const ff_msgs::FlightMode &flight_mode_msg)
Definition: graph_vio_simulator.cc:36
bool AddMeasurementsAndUpdateIfReady(const localization_common::Time ¤t_time)
Definition: graph_vio_simulator.cc:40
Definition: graph_vio_simulator_params.h:22
void BufferImuMsg(const sensor_msgs::Imu &imu_msg)
Definition: graph_vio_simulator.cc:34
void BufferOpticalFlowMsg(const ff_msgs::Feature2dArray &feature_array_msg)
Definition: graph_vio_simulator.cc:26
double Time
Definition: time.h:23