base_local_planner
alignment_cost_function.h
Go to the documentation of this file.
1 #ifndef base_local_planner_alignment_cost_function_h_
2 #define base_local_planner_alignment_cost_function_h_
3 
5 #include <Eigen/Core>
6 
8 {
9 
11 {
12 
13 public:
14 
16  virtual ~AlignmentCostFunction();
17 
18  double scoreTrajectory(Trajectory &traj);
19 
20  bool prepare() {return true;}
21 
22  void setDesiredOrientation(double theta) {theta_desired_ = theta;}
24 
25 private:
26 
29 
30 };
31 
32 }// namespace
33 
34 #endif
base_local_planner::AlignmentCostFunction::theta_desired_
double theta_desired_
Desired orientation.
Definition: alignment_cost_function.h:28
base_local_planner::AlignmentCostFunction::AlignmentCostFunction
AlignmentCostFunction()
Definition: alignment_cost_function.cpp:7
base_local_planner::AlignmentCostFunction::scoreTrajectory
double scoreTrajectory(Trajectory &traj)
Definition: alignment_cost_function.cpp:18
base_local_planner::TrajectoryCostFunction
Provides an interface for critics of trajectories During each sampling run, a batch of many trajector...
Definition: trajectory_cost_function.h:87
base_local_planner::AlignmentCostFunction::getDesiredOrientation
double getDesiredOrientation()
Definition: alignment_cost_function.h:23
base_local_planner::AlignmentCostFunction::prepare
bool prepare()
Definition: alignment_cost_function.h:20
base_local_planner::AlignmentCostFunction::setDesiredOrientation
void setDesiredOrientation(double theta)
Definition: alignment_cost_function.h:22
base_local_planner::AlignmentCostFunction::~AlignmentCostFunction
virtual ~AlignmentCostFunction()
Definition: alignment_cost_function.cpp:13
base_local_planner::Trajectory
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:76
base_local_planner::AlignmentCostFunction
Definition: alignment_cost_function.h:10
base_local_planner
Definition: alignment_cost_function.h:7
trajectory_cost_function.h