![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <graph_localizer/graph_localizer.h>#include <imu_integration/utilities.h>#include <localization_common/combined_nav_state.h>#include <localization_common/time.h>#include <gtsam/geometry/Pose3.h>#include <gtsam/navigation/CombinedImuFactor.h>#include <rviz/display_context.h>#include <rviz/ogre_helpers/axes.h>#include <OgreQuaternion.h>#include <OgreVector3.h>#include <memory>#include <utility>#include <string>#include <vector>

Go to the source code of this file.
Namespaces | |
| localization_rviz_plugins | |
Macros | |
| #define | LOCALIZATION_RVIZ_PLUGINS_UTILITIES_H_ |
Functions | |
| Ogre::Vector3 | localization_rviz_plugins::ogrePosition (const gtsam::Pose3 &pose) |
| Ogre::Vector3 | localization_rviz_plugins::ogrePosition (const gtsam::Point3 &point) |
| Ogre::Quaternion | localization_rviz_plugins::ogreQuaternion (const gtsam::Pose3 &pose) |
| boost::optional< gtsam::Pose3 > | localization_rviz_plugins::currentFrameTFrame (const std::string &frame_id, const ros::Time timestamp, const rviz::DisplayContext &context) |
| std::unique_ptr< rviz::Axes > | localization_rviz_plugins::axisFromPose (const gtsam::Pose3 &pose, const double scale, Ogre::SceneManager *scene_manager, Ogre::SceneNode *scene_node) |
| boost::optional< lc::CombinedNavState > | localization_rviz_plugins::firstCombinedNavState (const graph_localizer::GraphLocalizer &graph_localizer, const gtsam::CombinedImuFactor *const imu_factor) |
| boost::optional< lc::CombinedNavState > | localization_rviz_plugins::pimPredict (const graph_localizer::GraphLocalizer &graph_localizer, const gtsam::CombinedImuFactor *const imu_factor) |
| std::pair< Ogre::Quaternion, double > | localization_rviz_plugins::getOrientationAndLength (const gtsam::Point3 &point_a, const gtsam::Point3 &point_b) |
| #define LOCALIZATION_RVIZ_PLUGINS_UTILITIES_H_ |