38 #ifndef OBSTACLE_COST_FUNCTION_H_ 39 #define OBSTACLE_COST_FUNCTION_H_ 64 void setParams(
double max_trans_vel,
double max_scaling_factor,
double scaling_speed);
65 void setFootprint(std::vector<geometry_msgs::Point> footprint_spec);
74 std::vector<geometry_msgs::Point> footprint_spec,
void setFootprint(std::vector< geometry_msgs::Point > footprint_spec)
base_local_planner::WorldModel * world_model_
static double getScalingFactor(Trajectory &traj, double scaling_speed, double max_trans_vel, double max_scaling_factor)
ObstacleCostFunction(costmap_2d::Costmap2D *costmap)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void setSumScores(bool score_sums)
static double footprintCost(const double &x, const double &y, const double &th, double scale, std::vector< geometry_msgs::Point > footprint_spec, costmap_2d::Costmap2D *costmap, base_local_planner::WorldModel *world_model)
double scoreTrajectory(Trajectory &traj)
TFSIMD_FORCE_INLINE const tfScalar & x() const
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed)
Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajec...
double max_scaling_factor_
Provides an interface for critics of trajectories During each sampling run, a batch of many trajector...
std::vector< geometry_msgs::Point > footprint_spec_
costmap_2d::Costmap2D * costmap_
Holds a trajectory generated by considering an x, y, and theta velocity.