52 const geometry_msgs::Pose2D& goal,
53 const nav_2d_msgs::Path2D& global_plan)
55 double dx = pose.x - goal.x;
56 double dy = pose.y - goal.y;
57 double sq_dist = dx * dx + dy * dy;
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
virtual double scorePose(const geometry_msgs::Pose2D &pose)
Retrieve the score for a single pose.
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string ¶m_name, const param_t &default_value)
geometry_msgs::Pose2D getForwardPose(const geometry_msgs::Pose2D &pose, double distance)
Projects the given pose forward the specified distance in the x direction.
Scores trajectories based on how far from the global path the front of the robot ends up...
double forward_point_distance_
ros::NodeHandle critic_nh_
double getScale() const override
nav_core2::Costmap::Ptr costmap_
double scorePose(const geometry_msgs::Pose2D &pose) override
Retrieve the score for a single pose.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)