class that defines the skidpad path algorithm
More...
#include <skidpad.hpp>
class that defines the skidpad path algorithm
Definition at line 23 of file skidpad.hpp.
◆ Skidpad() [1/2]
◆ Skidpad() [2/2]
◆ align_cones_with_icp()
| Eigen::Matrix4f Skidpad::align_cones_with_icp |
( |
const std::vector< Cone > & |
cone_array | ) |
|
|
private |
Aligns detected cones with reference cones using ICP.
- Parameters
-
- Returns
- Eigen::Matrix4f Transformation matrix, or identity if ICP fails
Definition at line 18 of file skidpad.cpp.
◆ find_closest_path_index()
Finds the closest point index in a path to a given pose.
- Parameters
-
| path | Path to search |
| pose | Reference pose |
- Returns
- size_t Index of closest point
Definition at line 60 of file skidpad.cpp.
◆ skidpad_path()
Generate a path for skidpad course.
- Parameters
-
| cone_array | The array of cones representing the track |
| pose | The current pose of the vehicle |
- Returns
- std::vector<PathPoint> The generated path
Definition at line 85 of file skidpad.cpp.
◆ config_
◆ hardcoded_path_
| std::vector<PathPoint> Skidpad::hardcoded_path_ |
|
private |
◆ predefined_path_
| std::vector<PathPoint> Skidpad::predefined_path_ |
|
private |
◆ reference_cones_
| std::vector<std::pair<double, double> > Skidpad::reference_cones_ |
|
private |
◆ skidpad_data_loaded_
| bool Skidpad::skidpad_data_loaded_ = false |
|
private |
The documentation for this class was generated from the following files: