Public Member Functions | Private Attributes | List of all members
f2c::obj::CompleteTurnPathObj< T, R > Class Template Reference

Class to compute the cost of turning from one point to another. More...

#include <complete_turn_path_obj.h>

Inheritance diagram for f2c::obj::CompleteTurnPathObj< T, R >:
Inheritance graph
[legend]

Public Member Functions

 CompleteTurnPathObj (const F2CRobot &params)
 
 CompleteTurnPathObj (const F2CRobot &params, const T &turn_planner)
 
virtual double computeCost (const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CMultiPoint &ps, const F2CSwath &s)
 
virtual double computeCost (const F2CMultiPoint &ps, const F2CSwaths &s)
 
virtual double computeCost (const F2CPoint &p, const F2CSwath &s)
 
virtual double computeCost (const F2CPoint &p, double ang, const F2CSwath &s)
 
virtual double computeCost (const F2CPoint &p1, const F2CPoint &p2)
 
virtual double computeCost (const F2CPoint &p1, const F2CPoint &p2, double ang2)
 
virtual double computeCost (const F2CPoint &p1, double ang1, const F2CPoint &p2)
 
virtual double computeCost (const F2CPoint &p1, double ang1, const F2CPoint &p2, double ang2)
 
double computeCost (const F2CPoint &p1, double ang1, const F2CPoint &p2, double ang2) override
 
virtual double computeCost (const F2CRoute &r)
 Return the cost of covering a Route. More...
 
virtual double computeCost (const F2CSwath &s)
 
virtual double computeCost (const F2CSwath &s, const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CSwath &s, const F2CPoint &p)
 
virtual double computeCost (const F2CSwath &s, const F2CPoint &p, double ang)
 
virtual double computeCost (const F2CSwath &s1, const F2CSwath &s2)
 
virtual double computeCost (const F2CSwaths &s, const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CSwaths &swaths)
 Return the cost of covering a vector of swaths. More...
 
virtual double computeCost (const std::vector< F2CPoint > &ps)
 
void setRobot (const F2CRobot &robot)
 
void setTurnPlanner (const T &turner)
 
- Public Member Functions inherited from f2c::obj::RPObjective
virtual double computeCost (const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CMultiPoint &ps, const F2CSwath &s)
 
virtual double computeCost (const F2CMultiPoint &ps, const F2CSwaths &s)
 
virtual double computeCost (const F2CPoint &p, const F2CSwath &s)
 
virtual double computeCost (const F2CPoint &p, double ang, const F2CSwath &s)
 
virtual double computeCost (const F2CPoint &p1, const F2CPoint &p2)
 
virtual double computeCost (const F2CPoint &p1, const F2CPoint &p2, double ang2)
 
virtual double computeCost (const F2CPoint &p1, double ang1, const F2CPoint &p2)
 
virtual double computeCost (const F2CRoute &r)
 Return the cost of covering a Route. More...
 
virtual double computeCost (const F2CSwath &s)
 
virtual double computeCost (const F2CSwath &s, const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CSwath &s, const F2CPoint &p)
 
virtual double computeCost (const F2CSwath &s, const F2CPoint &p, double ang)
 
virtual double computeCost (const F2CSwath &s1, const F2CSwath &s2)
 
virtual double computeCost (const F2CSwaths &s, const F2CMultiPoint &ps)
 
virtual double computeCost (const F2CSwaths &swaths)
 Return the cost of covering a vector of swaths. More...
 
virtual double computeCost (const std::vector< F2CPoint > &ps)
 
- Public Member Functions inherited from f2c::obj::BaseObjective< RPObjective >
double computeCostWithMinimizingSign (const T1 &t1)
 Compute the cost function with minimizing sign. More...
 
double computeCostWithMinimizingSign (const T1 &t1, const T2 &t2)
 
double computeCostWithMinimizingSign (const T1 &t1, const T2 &t2, const T3 &t3)
 
double computeCostWithMinimizingSign (const T1 &t1, const T2 &t2, const T3 &t3, const T4 &t4)
 
virtual bool isMaximizing () const
 Return true if the objective is to maximize the cost function. More...
 
virtual bool isMinimizing () const
 Return true if the objective is to minimize the cost function. More...
 
virtual ~BaseObjective ()=default
 

Private Attributes

pp_objective
 
F2CRobot robot
 
turn_planner
 Planner that derives from f2c::pp::TurningBase. More...
 

Detailed Description

template<class T, class R = PPObjective>
class f2c::obj::CompleteTurnPathObj< T, R >

Class to compute the cost of turning from one point to another.

This is the closest result to the real cost of executing the path plan, as it actually compute all the turns.

Warning
Do not use this objective function with slow planners as too many turns may need to be computed for a simple path.

Definition at line 26 of file complete_turn_path_obj.h.

Constructor & Destructor Documentation

◆ CompleteTurnPathObj() [1/2]

template<class T , class R >
f2c::obj::CompleteTurnPathObj< T, R >::CompleteTurnPathObj ( const F2CRobot params)
explicit

Definition at line 58 of file complete_turn_path_obj.h.

◆ CompleteTurnPathObj() [2/2]

template<class T , class R >
f2c::obj::CompleteTurnPathObj< T, R >::CompleteTurnPathObj ( const F2CRobot params,
const T &  turn_planner 
)
explicit

Definition at line 63 of file complete_turn_path_obj.h.

Member Function Documentation

◆ computeCost() [1/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of covering all the points of ps

Parameters
psvector of points
Returns
Cost value

Definition at line 63 of file rp_objective.cpp.

◆ computeCost() [2/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from the last point of ps to the swath s

Parameters
psvector of points (end point)
sStart point (start of the swath)
Returns
Cost value

Definition at line 88 of file rp_objective.cpp.

◆ computeCost() [3/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from the last point of ps to the first swath of s

Parameters
psvector of points (end point)
sStart point (start of the first swath)
Returns
Cost value

Definition at line 96 of file rp_objective.cpp.

◆ computeCost() [4/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p to swath s

Parameters
pStart point
sEnd point (start of the swath)
Returns
Cost value

Definition at line 46 of file rp_objective.cpp.

◆ computeCost() [5/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p to swath s

Parameters
pStart point
angAngle of the robot in p
sEnd point (start of the swath)
Returns
Cost value

Definition at line 50 of file rp_objective.cpp.

◆ computeCost() [6/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p1 to point p2

Parameters
p1Start point
p2End point
Returns
Cost value

Definition at line 11 of file rp_objective.cpp.

◆ computeCost() [7/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p1 to point p2

Parameters
p1Start point
p2End point
ang2Angle of the robot in p2
Returns
Cost value

Definition at line 22 of file rp_objective.cpp.

◆ computeCost() [8/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p1 to point p2

Parameters
p1Start point
ang1Angle of the robot in p1
p2End point
Returns
Cost value

Definition at line 16 of file rp_objective.cpp.

◆ computeCost() [9/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from point p1 to point p2

Parameters
p1Start point
ang1Angle of the robot in p1
p2End point
ang2Angle of the robot in p2
Returns
Cost value

Definition at line 27 of file rp_objective.cpp.

◆ computeCost() [10/19]

template<class T , class R >
double f2c::obj::CompleteTurnPathObj< T, R >::computeCost ( const F2CPoint p1,
double  ang1,
const F2CPoint p2,
double  ang2 
)
overridevirtual

Compute the cost of doing the turn between p1 with angle ang1 to p2 with angle ang2

Reimplemented from f2c::obj::RPObjective.

Definition at line 79 of file complete_turn_path_obj.h.

◆ computeCost() [11/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of covering a Route.

Costs of each swath + Cost of going from one to another.

Parameters
rRoute
Returns
Cost value

Definition at line 120 of file rp_objective.cpp.

◆ computeCost() [12/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of covering a swath

Parameters
sSwath
Returns
Cost value

Definition at line 100 of file rp_objective.cpp.

◆ computeCost() [13/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from swath s to the first point of ps

Parameters
sStart point (end of the swath)
psvector of points
Returns
Cost value

Definition at line 74 of file rp_objective.cpp.

◆ computeCost() [14/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from swath s to point p

Parameters
sStart point (end of the swath)
pEnd point
Returns
Cost value

Definition at line 32 of file rp_objective.cpp.

◆ computeCost() [15/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from swath s to point p

Parameters
sStart point (end of the swath)
pEnd point
angAngle of the robot in p
Returns
Cost value

Definition at line 41 of file rp_objective.cpp.

◆ computeCost() [16/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from swath s to point p

Parameters
s1Start point (end of the swath)
s2End point (start of the swath)
Returns
Cost value

Definition at line 36 of file rp_objective.cpp.

◆ computeCost() [17/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of going from the last swath of s to the first point of ps

Parameters
sStart point (end of the last swath)
psvector of points (first point)
Returns
Cost value

Definition at line 81 of file rp_objective.cpp.

◆ computeCost() [18/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of covering a vector of swaths.

Costs of each swath + Cost of going from one to another. The order may affect the cost.

Parameters
sSwaths
Returns
Cost value

Definition at line 108 of file rp_objective.cpp.

◆ computeCost() [19/19]

template<class T , class R = PPObjective>
double f2c::obj::RPObjective::computeCost

Return the cost of covering all the points of ps

Parameters
psvector of points
Returns
Cost value

Definition at line 55 of file rp_objective.cpp.

◆ setRobot()

template<class T , class R >
void f2c::obj::CompleteTurnPathObj< T, R >::setRobot ( const F2CRobot robot)

Definition at line 68 of file complete_turn_path_obj.h.

◆ setTurnPlanner()

template<class T , class R >
void f2c::obj::CompleteTurnPathObj< T, R >::setTurnPlanner ( const T &  turner)

Definition at line 73 of file complete_turn_path_obj.h.

Member Data Documentation

◆ pp_objective

template<class T , class R = PPObjective>
R f2c::obj::CompleteTurnPathObj< T, R >::pp_objective
private

Definition at line 53 of file complete_turn_path_obj.h.

◆ robot

template<class T , class R = PPObjective>
F2CRobot f2c::obj::CompleteTurnPathObj< T, R >::robot
private

Definition at line 52 of file complete_turn_path_obj.h.

◆ turn_planner

template<class T , class R = PPObjective>
T f2c::obj::CompleteTurnPathObj< T, R >::turn_planner
private

Planner that derives from f2c::pp::TurningBase.

Definition at line 51 of file complete_turn_path_obj.h.


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


fields2cover
Author(s):
autogenerated on Fri Apr 25 2025 02:18:31