base_local_planner
cmd_vel_cost_function.h
Go to the documentation of this file.
1 #ifndef base_local_planner_cmd_vel_cost_function_h_
2 #define base_local_planner_cmd_vel_cost_function_h_
3 
5 #include <Eigen/Core>
6 
7 namespace base_local_planner
8 {
9 
11 {
12 
13 public:
14 
16  virtual ~CmdVelCostFunction();
17 
18  double scoreTrajectory(Trajectory &traj);
19 
20  bool prepare() { return true; }
21 
29  void setCoefficients(double px, double nx, double py, double ny, double ptheta, double ntheta)
30  {
31  px_ = px;
32  nx_ = nx;
33  py_ = py;
34  ny_ = ny;
35  ptheta_ = ptheta;
36  ntheta_ = ntheta;
37  }
38 
39 private:
40 
42  double px_, nx_, py_, ny_, ptheta_, ntheta_;
43 
44 };
45 
46 }// namespace
47 
48 #endif
base_local_planner::CmdVelCostFunction::ptheta_
double ptheta_
Definition: cmd_vel_cost_function.h:42
base_local_planner::CmdVelCostFunction::py_
double py_
Definition: cmd_vel_cost_function.h:42
base_local_planner::CmdVelCostFunction::ntheta_
double ntheta_
Definition: cmd_vel_cost_function.h:42
base_local_planner::CmdVelCostFunction::CmdVelCostFunction
CmdVelCostFunction()
Definition: cmd_vel_cost_function.cpp:5
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::CmdVelCostFunction::ny_
double ny_
Definition: cmd_vel_cost_function.h:42
base_local_planner::CmdVelCostFunction::~CmdVelCostFunction
virtual ~CmdVelCostFunction()
Definition: cmd_vel_cost_function.cpp:16
base_local_planner::CmdVelCostFunction::setCoefficients
void setCoefficients(double px, double nx, double py, double ny, double ptheta, double ntheta)
Definition: cmd_vel_cost_function.h:29
base_local_planner::CmdVelCostFunction::px_
double px_
Cost function coefficients.
Definition: cmd_vel_cost_function.h:42
base_local_planner::Trajectory
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:76
base_local_planner::CmdVelCostFunction
Definition: cmd_vel_cost_function.h:10
base_local_planner::CmdVelCostFunction::prepare
bool prepare()
Definition: cmd_vel_cost_function.h:20
base_local_planner::CmdVelCostFunction::scoreTrajectory
double scoreTrajectory(Trajectory &traj)
Definition: cmd_vel_cost_function.cpp:21
base_local_planner
Definition: alignment_cost_function.h:7
base_local_planner::CmdVelCostFunction::nx_
double nx_
Definition: cmd_vel_cost_function.h:42
trajectory_cost_function.h