NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <graph_localizer_simulator.h>
Public Member Functions | |
GraphLocalizerSimulator (const GraphLocalizerSimulatorParams ¶ms, const std::string &graph_config_path_prefix) | |
void | BufferImuMsg (const sensor_msgs::Imu &imu_msg) |
void | BufferFlightModeMsg (const ff_msgs::FlightMode &flight_mode_msg) |
void | BufferGraphVIOStateMsg (const ff_msgs::GraphVIOState &graph_vio_state_msg) |
void | BufferVLVisualLandmarksMsg (const ff_msgs::VisualLandmarks &visual_landmarks_msg) |
void | BufferARVisualLandmarksMsg (const ff_msgs::VisualLandmarks &visual_landmarks_msg) |
bool | AddMeasurementsAndUpdateIfReady (const localization_common::Time ¤t_time) |
Public Member Functions inherited from ros_graph_localizer::RosGraphLocalizerWrapper | |
RosGraphLocalizerWrapper (const std::string &graph_config_path_prefix="") | |
void | LoadConfigs (const std::string &graph_config_path_prefix) |
void | ImuCallback (const sensor_msgs::Imu &imu_msg) |
void | FlightModeCallback (const ff_msgs::FlightMode &flight_mode) |
void | SparseMapVisualLandmarksCallback (const ff_msgs::VisualLandmarks &visual_landmarks_msg) |
void | ARVisualLandmarksCallback (const ff_msgs::VisualLandmarks &visual_landmarks_msg) |
bool | GraphVIOStateCallback (const ff_msgs::GraphVIOState &graph_vio_state_msg) |
void | Update () |
bool | Initialized () const |
void | ResetLocalizer () |
void | ResetWorldTDock () |
boost::optional< localization_common::Time > | LatestTimestamp () const |
boost::optional< gtsam::Pose3 > | LatestPose () const |
boost::optional< gtsam::Pose3 > | WorldTDock () const |
boost::optional< ff_msgs::GraphLocState > | GraphLocStateMsg () |
std::unique_ptr< graph_localizer::GraphLocalizer > & | graph_localizer () |
const std::unique_ptr< graph_localizer::GraphLocalizer > & | graph_localizer () const |
localization_analysis::GraphLocalizerSimulator::GraphLocalizerSimulator | ( | const GraphLocalizerSimulatorParams & | params, |
const std::string & | graph_config_path_prefix | ||
) |
bool localization_analysis::GraphLocalizerSimulator::AddMeasurementsAndUpdateIfReady | ( | const localization_common::Time & | current_time | ) |
void localization_analysis::GraphLocalizerSimulator::BufferARVisualLandmarksMsg | ( | const ff_msgs::VisualLandmarks & | visual_landmarks_msg | ) |
void localization_analysis::GraphLocalizerSimulator::BufferFlightModeMsg | ( | const ff_msgs::FlightMode & | flight_mode_msg | ) |
void localization_analysis::GraphLocalizerSimulator::BufferGraphVIOStateMsg | ( | const ff_msgs::GraphVIOState & | graph_vio_state_msg | ) |
void localization_analysis::GraphLocalizerSimulator::BufferImuMsg | ( | const sensor_msgs::Imu & | imu_msg | ) |
void localization_analysis::GraphLocalizerSimulator::BufferVLVisualLandmarksMsg | ( | const ff_msgs::VisualLandmarks & | visual_landmarks_msg | ) |