#include <perception.h>
Definition at line 38 of file perception.h.
◆ DockPerception()
◆ callback()
void DockPerception::callback |
( |
const sensor_msgs::LaserScanConstPtr & |
scan | ) |
|
|
private |
◆ extract()
Extract a DockCandidate from a cluster, filling in the lengths and slopes of each line found using ransac.
- Parameters
-
cluster | The pointer to the cluster to extract from. |
Definition at line 369 of file perception.cpp.
◆ fit()
Try to fit a dock to candidate.
- Parameters
-
candidate | The candidate to fit to. |
pose | The fitted pose, if successful. |
- Returns
- Fitness score (>0 if successful)
Definition at line 417 of file perception.cpp.
◆ getPose()
bool DockPerception::getPose |
( |
geometry_msgs::PoseStamped & |
pose, |
|
|
std::string |
frame = "" |
|
) |
| |
◆ isValid()
Method to check if the quaternion is valid.
- Parameters
-
- Returns
- True if quaternion is valid.
Definition at line 553 of file perception.cpp.
◆ start()
bool DockPerception::start |
( |
const geometry_msgs::PoseStamped & |
pose | ) |
|
Start dock detection.
- Parameters
-
pose | The initial estimate of dock pose |
Definition at line 105 of file perception.cpp.
◆ stop()
bool DockPerception::stop |
( |
| ) |
|
◆ debug_
bool DockPerception::debug_ |
|
private |
◆ debug_points_
◆ dock_
geometry_msgs::PoseStamped DockPerception::dock_ |
|
private |
◆ dock_mutex_
boost::mutex DockPerception::dock_mutex_ |
|
private |
◆ dock_pose_filter_
◆ dock_stamp_
◆ found_dock_
bool DockPerception::found_dock_ |
|
private |
◆ front_cloud_
◆ ideal_cloud_
◆ listener_
◆ max_alignment_error_
double DockPerception::max_alignment_error_ |
|
private |
◆ running_
bool DockPerception::running_ |
|
private |
◆ scan_sub_
◆ tracking_frame_
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: