![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Classes | |
| struct | LightCost |
| struct | Lighthouse |
| struct | Measurement |
| struct | SmoothCost |
| class | Solver |
| struct | Tracker |
Typedefs | |
| typedef std::map< uint8_t, Lighthouse > | LighthouseMap |
| typedef std::map< std::string, Tracker > | TrackerMap |
| typedef std::map< ros::Time, Measurement > | MeasurementMap |
| typedef std::map< ros::Time, geometry_msgs::TransformStamped > | CorrectionMap |
| typedef std::map< ros::Time, double[6]> | Trajectory |
| typedef std::map< ros::Time, std::map< uint8_t, std::map< std::string, std::map< uint8_t, std::map< uint8_t, std::vector< double > > > > > > | LightMeasurements |
Enumerations | |
| enum | Params { PARAM_PHASE, PARAM_TILT, PARAM_GIB_PHASE, PARAM_GIB_MAG, PARAM_CURVE, NUM_PARAMS } |
| enum | Errors { ERROR_GYR_BIAS, ERROR_GYR_SCALE, ERROR_ACC_BIAS, ERROR_ACC_SCALE, NUM_ERRORS } |
| enum | Motors { MOTOR_VERTICAL, MOTOR_HORIZONTAL, NUM_MOTORS } |
Functions | |
| void | SendStaticTransform (geometry_msgs::TransformStamped const &tfs) |
| void | SendDynamicTransform (geometry_msgs::TransformStamped const &tfs) |
| void | SendTransforms (std::string const &frame_world, std::string const &frame_vive, std::string const &frame_body, double registration[6], LighthouseMap const &lighthouses, TrackerMap const &trackers) |
| Eigen::Affine3d | CeresToEigen (double ceres[6], bool invert) |
| Eigen::Quaterniond | toQuaternion (double roll, double pitch, double yaw) |
| bool | ReadModificationVector (config_reader::ConfigReader *config, Eigen::Vector3d &modification_vector, Eigen::Quaterniond &modification_quaternion) |
| bool | ReadLighthouseConfig (config_reader::ConfigReader *config, std::map< std::string, Eigen::Affine3d > &lighthouses) |
| bool | ReadTrackerConfig (config_reader::ConfigReader *config, std::map< std::string, Tracker > &trackers) |
| bool | ReadRegistrationConfig (config_reader::ConfigReader *config, double T[6]) |
| void | LighthouseCallback (ff_hw_msgs::ViveLighthouses::ConstPtr const &msg, LighthouseMap &lighthouses) |
| void | TrackerCallback (ff_hw_msgs::ViveTrackers::ConstPtr const &msg, TrackerMap &trackers) |
| bool | SolvePnP (std::vector< cv::Point3f > const &obj, std::vector< cv::Point2f > const &img, Eigen::Affine3d &transform) |
| template<typename T > | |
| static bool | Kabsch (Eigen::Matrix< T, 3, Eigen::Dynamic > in, Eigen::Matrix< T, 3, Eigen::Dynamic > out, Eigen::Transform< T, 3, Eigen::Affine > &A, bool allowScale) |
| template<typename T > | |
| static void | Predict (T const *params, T const *xyz, T *ang, bool correct) |
| template<typename T > | |
| static void | Correct (T const *params, T *angle, bool correct) |
| template<typename T > | |
| void | TransformInPlace (const T transform[6], T x[3]) |
| template<typename T > | |
| void | InverseTransformInPlace (const T transform[6], T x[3]) |
| template<typename T > | |
| void | CombineTransforms (const T b[6], const T a[6], T ba[6]) |
| template<typename T > | |
| void | TransformError (const T a[6], const T b[6], T err[6]) |
Variables | |
| static constexpr size_t | NUM_SENSORS = 32 |
| typedef std::map<ros::Time, geometry_msgs::TransformStamped> vive_localization::CorrectionMap |
| typedef std::map<uint8_t, Lighthouse> vive_localization::LighthouseMap |
| typedef std::map<ros::Time, std::map<uint8_t, std::map<std::string, std::map<uint8_t, std::map<uint8_t, std::vector<double> > > > > > vive_localization::LightMeasurements |
| typedef std::map<ros::Time, Measurement> vive_localization::MeasurementMap |
| typedef std::map<std::string, Tracker> vive_localization::TrackerMap |
| typedef std::map<ros::Time, double[6]> vive_localization::Trajectory |
| Eigen::Affine3d vive_localization::CeresToEigen | ( | double | ceres[6], |
| bool | invert | ||
| ) |
|
inline |
|
static |
|
inline |
|
static |
| void vive_localization::LighthouseCallback | ( | ff_hw_msgs::ViveLighthouses::ConstPtr const & | msg, |
| LighthouseMap & | lighthouses | ||
| ) |
|
static |
| bool vive_localization::ReadLighthouseConfig | ( | config_reader::ConfigReader * | config, |
| std::map< std::string, Eigen::Affine3d > & | lighthouses | ||
| ) |
| bool vive_localization::ReadModificationVector | ( | config_reader::ConfigReader * | config, |
| Eigen::Vector3d & | modification_vector, | ||
| Eigen::Quaterniond & | modification_quaternion | ||
| ) |
| bool vive_localization::ReadRegistrationConfig | ( | config_reader::ConfigReader * | config, |
| double | T[6] | ||
| ) |
| bool vive_localization::ReadTrackerConfig | ( | config_reader::ConfigReader * | config, |
| std::map< std::string, Tracker > & | trackers | ||
| ) |
| void vive_localization::SendDynamicTransform | ( | geometry_msgs::TransformStamped const & | tfs | ) |
| void vive_localization::SendStaticTransform | ( | geometry_msgs::TransformStamped const & | tfs | ) |
| void vive_localization::SendTransforms | ( | std::string const & | frame_world, |
| std::string const & | frame_vive, | ||
| std::string const & | frame_body, | ||
| double | registration[6], | ||
| LighthouseMap const & | lighthouses, | ||
| TrackerMap const & | trackers | ||
| ) |
| bool vive_localization::SolvePnP | ( | std::vector< cv::Point3f > const & | obj, |
| std::vector< cv::Point2f > const & | img, | ||
| Eigen::Affine3d & | transform | ||
| ) |
| Eigen::Quaterniond vive_localization::toQuaternion | ( | double | roll, |
| double | pitch, | ||
| double | yaw | ||
| ) |
| void vive_localization::TrackerCallback | ( | ff_hw_msgs::ViveTrackers::ConstPtr const & | msg, |
| TrackerMap & | trackers | ||
| ) |
|
inline |
|
inline |
|
staticconstexpr |