NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Classes | |
struct | DepthCorrespondences |
class | DepthImage |
struct | DepthImageMeasurement |
struct | DepthOdometryMeasurement |
struct | FeaturePointsMeasurement |
class | GeneralPlane |
struct | HandrailPointsMeasurement |
class | HessianNormalPlane |
struct | ImageMeasurement |
struct | ImuMeasurement |
struct | MatchedProjection |
struct | MatchedProjectionsMeasurement |
struct | Measurement |
struct | Odometry |
class | Plane |
struct | PointCloudMeasurement |
class | PointNormalPlane |
struct | PoseMeasurement |
struct | PoseWithCovarianceMeasurement |
struct | RelativePoseWithCovarianceMeasurement |
struct | StandstillMeasurement |
struct | TimestampedHandrailPose |
struct | TimestampedPose |
Typedefs | |
using | ImagePoint = gtsam::Point2 |
using | MapPoint = gtsam::Point3 |
using | MatchedProjections = std::vector< MatchedProjection > |
using | PoseCovariance = Eigen::Matrix< double, 6, 6 > |
Enumerations | |
enum | FanSpeedMode { FanSpeedMode::kOff, FanSpeedMode::kQuiet, FanSpeedMode::kNominal, FanSpeedMode::kAggressive } |
Functions | |
MatchedProjectionsMeasurement | MakeMatchedProjectionsMeasurement (const ff_msgs::VisualLandmarks &visual_landmarks) |
HandrailPointsMeasurement | MakeHandrailPointsMeasurement (const ff_msgs::DepthLandmarks &depth_landmarks, const TimestampedHandrailPose &world_T_handrail) |
Plane | MakeHandrailPlane (const gtsam::Pose3 &world_T_handrail, const double distance_to_wall) |
std::pair< gtsam::Point3, gtsam::Point3 > | MakeHandrailEndpoints (const gtsam::Pose3 &world_T_handrail, const double length) |
MatchedProjectionsMeasurement | FrameChangeMatchedProjectionsMeasurement (const MatchedProjectionsMeasurement &matched_projections_measurement, const gtsam::Pose3 &new_frame_T_measurement_origin) |
FeaturePointsMeasurement | MakeFeaturePointsMeasurement (const ff_msgs::Feature2dArray &optical_flow_tracks) |
FanSpeedMode | ConvertFanSpeedMode (const uint8_t speed) |
boost::optional< ImageMeasurement > | MakeImageMeasurement (const sensor_msgs::ImageConstPtr &image_msg, const std::string &encoding) |
PointCloudMeasurement | MakePointCloudMeasurement (const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg) |
boost::optional< DepthImageMeasurement > | MakeDepthImageMeasurement (const sensor_msgs::PointCloud2ConstPtr &depth_cloud_msg, const sensor_msgs::ImageConstPtr &image_msg, const Eigen::Affine3d image_A_depth_cam=Eigen::Affine3d::Identity()) |
template<typename PointType > | |
sensor_msgs::PointCloud2 | MakePointCloudMsg (const pcl::PointCloud< PointType > &cloud, const localization_common::Time timestamp, const std::string frame) |
localization_common::PoseWithCovariance | MakePoseWithCovariance (const geometry_msgs::PoseWithCovariance &msg) |
Odometry | MakeOdometry (const ff_msgs::Odometry &msg) |
DepthCorrespondences | MakeDepthCorrespondences (const std::vector< ff_msgs::DepthCorrespondence > &msgs) |
DepthOdometryMeasurement | MakeDepthOdometryMeasurement (const ff_msgs::DepthOdometry &depth_odometry_msg) |
DepthCorrespondences | MakeDepthCorrespondences (const ff_msgs::DepthOdometry &msg) |
using localization_measurements::ImagePoint = typedef gtsam::Point2 |
using localization_measurements::MapPoint = typedef gtsam::Point3 |
using localization_measurements::MatchedProjections = typedef std::vector<MatchedProjection> |
typedef Eigen::Matrix< double, 6, 6 > localization_measurements::PoseCovariance |
|
strong |
FanSpeedMode localization_measurements::ConvertFanSpeedMode | ( | const uint8_t | speed | ) |
MatchedProjectionsMeasurement localization_measurements::FrameChangeMatchedProjectionsMeasurement | ( | const MatchedProjectionsMeasurement & | matched_projections_measurement, |
const gtsam::Pose3 & | new_frame_T_measurement_origin | ||
) |
DepthCorrespondences localization_measurements::MakeDepthCorrespondences | ( | const ff_msgs::DepthOdometry & | msg | ) |
DepthCorrespondences localization_measurements::MakeDepthCorrespondences | ( | const std::vector< ff_msgs::DepthCorrespondence > & | msgs | ) |
boost::optional< DepthImageMeasurement > localization_measurements::MakeDepthImageMeasurement | ( | const sensor_msgs::PointCloud2ConstPtr & | depth_cloud_msg, |
const sensor_msgs::ImageConstPtr & | image_msg, | ||
const Eigen::Affine3d | image_A_depth_cam = Eigen::Affine3d::Identity() |
||
) |
DepthOdometryMeasurement localization_measurements::MakeDepthOdometryMeasurement | ( | const ff_msgs::DepthOdometry & | depth_odometry_msg | ) |
FeaturePointsMeasurement localization_measurements::MakeFeaturePointsMeasurement | ( | const ff_msgs::Feature2dArray & | optical_flow_tracks | ) |
std::pair< gtsam::Point3, gtsam::Point3 > localization_measurements::MakeHandrailEndpoints | ( | const gtsam::Pose3 & | world_T_handrail, |
const double | length | ||
) |
Plane localization_measurements::MakeHandrailPlane | ( | const gtsam::Pose3 & | world_T_handrail, |
const double | distance_to_wall | ||
) |
HandrailPointsMeasurement localization_measurements::MakeHandrailPointsMeasurement | ( | const ff_msgs::DepthLandmarks & | depth_landmarks, |
const TimestampedHandrailPose & | world_T_handrail | ||
) |
boost::optional< ImageMeasurement > localization_measurements::MakeImageMeasurement | ( | const sensor_msgs::ImageConstPtr & | image_msg, |
const std::string & | encoding | ||
) |
MatchedProjectionsMeasurement localization_measurements::MakeMatchedProjectionsMeasurement | ( | const ff_msgs::VisualLandmarks & | visual_landmarks | ) |
Odometry localization_measurements::MakeOdometry | ( | const ff_msgs::Odometry & | msg | ) |
PointCloudMeasurement localization_measurements::MakePointCloudMeasurement | ( | const sensor_msgs::PointCloud2ConstPtr & | point_cloud_msg | ) |
sensor_msgs::PointCloud2 localization_measurements::MakePointCloudMsg | ( | const pcl::PointCloud< PointType > & | cloud, |
const localization_common::Time | timestamp, | ||
const std::string | frame | ||
) |
lc::PoseWithCovariance localization_measurements::MakePoseWithCovariance | ( | const geometry_msgs::PoseWithCovariance & | msg | ) |