|
| Inspection (ros::NodeHandle *nh, ff_util::ConfigServer *cfg) |
|
void | ReadParam () |
|
bool | RemoveInspectionPose () |
|
geometry_msgs::PoseArray | GetCurrentInspectionPose () |
|
bool | NextInspectionPose () |
|
bool | RedoInspectionPose () |
|
geometry_msgs::PoseArray | GetInspectionPoses () |
|
int | GetCurrentCounter () |
|
int | GetSurveySize () |
|
double | GetDistanceToTarget () |
|
bool | GenerateAnomalySurvey (geometry_msgs::PoseArray &points_anomaly) |
|
bool | GenerateGeometrySurvey (geometry_msgs::PoseArray &points_geometry) |
|
bool | GeneratePanoramaSurvey (geometry_msgs::PoseArray &points_panorama) |
|
bool | GenerateVolumetricSurvey (geometry_msgs::PoseArray &points_volume) |
|
|
void | ConnectedCallback () |
|
void | CheckZonesTimeoutCallback () |
|
void | CheckMapTimeoutCallback () |
|
bool | TransformList (geometry_msgs::PoseArray points_in, geometry_msgs::PoseArray &points_out, Eigen::Affine3d target_transform) |
|
bool | VisibilityConstraint (geometry_msgs::PoseArray &points, Eigen::Affine3d target_transform) |
|
bool | PointInsideCuboid (geometry_msgs::Point const &x, geometry_msgs::Vector3 const &cubemin, geometry_msgs::Vector3 const &cubemax) |
|
bool | ZonesConstraint (geometry_msgs::PoseArray &points) |
|
bool | ObstaclesConstraint (geometry_msgs::PoseArray &points) |
|
void | DrawPoseMarkers (geometry_msgs::PoseArray &points, ros::Publisher &publisher) |
|
void | DrawCameraFrustum () |
|
bool | GenerateSortedList (geometry_msgs::PoseArray &points) |
|
The documentation for this class was generated from the following files:
- astrobee/behaviors/inspection/include/inspection/inspection.h
- astrobee/behaviors/inspection/src/anomaly_survey.cc
- astrobee/behaviors/inspection/src/inspection.cc