Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
DockPerception Class Reference

#include <perception.h>

Public Member Functions

 DockPerception (ros::NodeHandle &nh)
 
bool getPose (geometry_msgs::PoseStamped &pose, std::string frame="")
 Get the pose of the dock. More...
 
bool start (const geometry_msgs::PoseStamped &pose)
 Start dock detection. More...
 
bool stop ()
 Stop tracking the dock. More...
 

Private Member Functions

void callback (const sensor_msgs::LaserScanConstPtr &scan)
 Callback to process laser scans. More...
 
DockCandidatePtr extract (laser_processor::SampleSet *cluster)
 Extract a DockCandidate from a cluster, filling in the lengths and slopes of each line found using ransac. More...
 
double fit (const DockCandidatePtr &candidate, geometry_msgs::Pose &pose)
 Try to fit a dock to candidate. More...
 

Static Private Member Functions

static bool isValid (const tf::Quaternion &q)
 Method to check if the quaternion is valid. More...
 

Private Attributes

bool debug_
 
ros::Publisher debug_points_
 
geometry_msgs::PoseStamped dock_
 
boost::mutex dock_mutex_
 
LinearPoseFilter2DPtr dock_pose_filter_
 
ros::Time dock_stamp_
 
bool found_dock_
 
std::vector< geometry_msgs::Pointfront_cloud_
 
std::vector< geometry_msgs::Pointideal_cloud_
 
tf::TransformListener listener_
 
double max_alignment_error_
 
bool running_
 
ros::Subscriber scan_sub_
 
std::string tracking_frame_
 Low pass filter object for filtering dock poses. More...
 

Detailed Description

Definition at line 38 of file perception.h.

Constructor & Destructor Documentation

DockPerception::DockPerception ( ros::NodeHandle nh)
explicit

Definition at line 40 of file perception.cpp.

Member Function Documentation

void DockPerception::callback ( const sensor_msgs::LaserScanConstPtr &  scan)
private

Callback to process laser scans.

Definition at line 174 of file perception.cpp.

DockCandidatePtr DockPerception::extract ( laser_processor::SampleSet cluster)
private

Extract a DockCandidate from a cluster, filling in the lengths and slopes of each line found using ransac.

Parameters
clusterThe pointer to the cluster to extract from.

Definition at line 369 of file perception.cpp.

double DockPerception::fit ( const DockCandidatePtr candidate,
geometry_msgs::Pose pose 
)
private

Try to fit a dock to candidate.

Parameters
candidateThe candidate to fit to.
poseThe fitted pose, if successful.
Returns
Fitness score (>0 if successful)

Definition at line 417 of file perception.cpp.

bool DockPerception::getPose ( geometry_msgs::PoseStamped &  pose,
std::string  frame = "" 
)

Get the pose of the dock.

Definition at line 120 of file perception.cpp.

bool DockPerception::isValid ( const tf::Quaternion q)
staticprivate

Method to check if the quaternion is valid.

Parameters
qQuaternion to check.
Returns
True if quaternion is valid.

Definition at line 553 of file perception.cpp.

bool DockPerception::start ( const geometry_msgs::PoseStamped &  pose)

Start dock detection.

Parameters
poseThe initial estimate of dock pose

Definition at line 105 of file perception.cpp.

bool DockPerception::stop ( )

Stop tracking the dock.

Definition at line 114 of file perception.cpp.

Member Data Documentation

bool DockPerception::debug_
private

Definition at line 85 of file perception.h.

ros::Publisher DockPerception::debug_points_
private

Definition at line 103 of file perception.h.

geometry_msgs::PoseStamped DockPerception::dock_
private

Definition at line 92 of file perception.h.

boost::mutex DockPerception::dock_mutex_
private

Definition at line 94 of file perception.h.

LinearPoseFilter2DPtr DockPerception::dock_pose_filter_
private

Definition at line 87 of file perception.h.

ros::Time DockPerception::dock_stamp_
private

Definition at line 98 of file perception.h.

bool DockPerception::found_dock_
private

Definition at line 96 of file perception.h.

std::vector<geometry_msgs::Point> DockPerception::front_cloud_
private

Definition at line 108 of file perception.h.

std::vector<geometry_msgs::Point> DockPerception::ideal_cloud_
private

Definition at line 106 of file perception.h.

tf::TransformListener DockPerception::listener_
private

Definition at line 82 of file perception.h.

double DockPerception::max_alignment_error_
private

Definition at line 100 of file perception.h.

bool DockPerception::running_
private

Definition at line 84 of file perception.h.

ros::Subscriber DockPerception::scan_sub_
private

Definition at line 81 of file perception.h.

std::string DockPerception::tracking_frame_
private

Low pass filter object for filtering dock poses.

Definition at line 90 of file perception.h.


The documentation for this class was generated from the following files:


caster_app
Author(s): Ye Tian
autogenerated on Wed Dec 18 2019 03:34:44