NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
localization_measurements Namespace Reference

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< ImageMeasurementMakeImageMeasurement (const sensor_msgs::ImageConstPtr &image_msg, const std::string &encoding)
 
PointCloudMeasurement MakePointCloudMeasurement (const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg)
 
boost::optional< DepthImageMeasurementMakeDepthImageMeasurement (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)
 

Typedef Documentation

◆ ImagePoint

using localization_measurements::ImagePoint = typedef gtsam::Point2

◆ MapPoint

using localization_measurements::MapPoint = typedef gtsam::Point3

◆ MatchedProjections

◆ PoseCovariance

typedef Eigen::Matrix< double, 6, 6 > localization_measurements::PoseCovariance

Enumeration Type Documentation

◆ FanSpeedMode

Enumerator
kOff 
kQuiet 
kNominal 
kAggressive 

Function Documentation

◆ ConvertFanSpeedMode()

FanSpeedMode localization_measurements::ConvertFanSpeedMode ( const uint8_t  speed)

◆ FrameChangeMatchedProjectionsMeasurement()

MatchedProjectionsMeasurement localization_measurements::FrameChangeMatchedProjectionsMeasurement ( const MatchedProjectionsMeasurement matched_projections_measurement,
const gtsam::Pose3 &  new_frame_T_measurement_origin 
)

◆ MakeDepthCorrespondences() [1/2]

DepthCorrespondences localization_measurements::MakeDepthCorrespondences ( const ff_msgs::DepthOdometry &  msg)

◆ MakeDepthCorrespondences() [2/2]

DepthCorrespondences localization_measurements::MakeDepthCorrespondences ( const std::vector< ff_msgs::DepthCorrespondence > &  msgs)

◆ MakeDepthImageMeasurement()

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() 
)

◆ MakeDepthOdometryMeasurement()

DepthOdometryMeasurement localization_measurements::MakeDepthOdometryMeasurement ( const ff_msgs::DepthOdometry &  depth_odometry_msg)

◆ MakeFeaturePointsMeasurement()

FeaturePointsMeasurement localization_measurements::MakeFeaturePointsMeasurement ( const ff_msgs::Feature2dArray &  optical_flow_tracks)

◆ MakeHandrailEndpoints()

std::pair< gtsam::Point3, gtsam::Point3 > localization_measurements::MakeHandrailEndpoints ( const gtsam::Pose3 &  world_T_handrail,
const double  length 
)

◆ MakeHandrailPlane()

Plane localization_measurements::MakeHandrailPlane ( const gtsam::Pose3 &  world_T_handrail,
const double  distance_to_wall 
)

◆ MakeHandrailPointsMeasurement()

HandrailPointsMeasurement localization_measurements::MakeHandrailPointsMeasurement ( const ff_msgs::DepthLandmarks &  depth_landmarks,
const TimestampedHandrailPose world_T_handrail 
)

◆ MakeImageMeasurement()

boost::optional< ImageMeasurement > localization_measurements::MakeImageMeasurement ( const sensor_msgs::ImageConstPtr &  image_msg,
const std::string &  encoding 
)

◆ MakeMatchedProjectionsMeasurement()

MatchedProjectionsMeasurement localization_measurements::MakeMatchedProjectionsMeasurement ( const ff_msgs::VisualLandmarks &  visual_landmarks)

◆ MakeOdometry()

Odometry localization_measurements::MakeOdometry ( const ff_msgs::Odometry &  msg)

◆ MakePointCloudMeasurement()

PointCloudMeasurement localization_measurements::MakePointCloudMeasurement ( const sensor_msgs::PointCloud2ConstPtr &  point_cloud_msg)

◆ MakePointCloudMsg()

template<typename PointType >
sensor_msgs::PointCloud2 localization_measurements::MakePointCloudMsg ( const pcl::PointCloud< PointType > &  cloud,
const localization_common::Time  timestamp,
const std::string  frame 
)

◆ MakePoseWithCovariance()

lc::PoseWithCovariance localization_measurements::MakePoseWithCovariance ( const geometry_msgs::PoseWithCovariance &  msg)