52 const geometry_msgs::Pose2D& goal,
53 const nav_2d_msgs::Path2D& global_plan)
60 double angle_to_goal = atan2(goal.y - pose.y, goal.x - pose.x);
62 nav_2d_msgs::Path2D target_poses = global_plan;
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.
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
ros::NodeHandle critic_nh_
double scorePose(const geometry_msgs::Pose2D &pose) override
Retrieve the score for a single pose.
Scores trajectories based on whether the robot ends up pointing toward the eventual goal...
double forward_point_distance_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)