Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap. More...
#include <navfn_ros.h>
Public Member Functions | |
bool | computePotential (const geometry_msgs::Point &world_point) |
Computes the full navigation function for the map given a point in the world to start from. | |
bool | getPlanFromPotential (const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first). | |
double | getPointPotential (const geometry_msgs::Point &world_point) |
Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first). | |
void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
Initialization function for the NavFnROS object. | |
bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan) |
Given a goal pose in the world, compute a plan. | |
bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
Given a goal pose in the world, compute a plan. | |
bool | makePlanService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp) |
NavfnROS (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | |
Constructor for the NavFnROS object. | |
NavfnROS () | |
Default constructor for the NavFnROS object. | |
void | publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, double r, double g, double b, double a) |
Publish a path for visualization purposes. | |
bool | validPointPotential (const geometry_msgs::Point &world_point, double tolerance) |
Check for a valid potential value at a given point in the world (Note: You should call computePotential first). | |
bool | validPointPotential (const geometry_msgs::Point &world_point) |
Check for a valid potential value at a given point in the world (Note: You should call computePotential first). | |
~NavfnROS () | |
Protected Member Functions | |
virtual void | getCostmap (costmap_2d::Costmap2D &costmap) |
Store a copy of the current costmap in costmap. Called by makePlan. | |
Protected Attributes | |
bool | allow_unknown_ |
double | circumscribed_radius_ |
costmap_2d::Costmap2DROS * | costmap_ros_ |
double | inflation_radius_ |
bool | initialized_ |
double | inscribed_radius_ |
ros::Publisher | plan_pub_ |
boost::shared_ptr< NavFn > | planner_ |
pcl_ros::Publisher< PotarrPoint > | potarr_pub_ |
bool | visualize_potential_ |
Private Member Functions | |
void | clearRobotCell (const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my) |
void | mapToWorld (double mx, double my, double &wx, double &wy) |
double | sq_distance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2) |
Private Attributes | |
costmap_2d::Costmap2D | costmap_ |
costmap_2d::Costmap2DPublisher * | costmap_publisher_ |
double | default_tolerance_ |
ros::ServiceServer | make_plan_srv_ |
boost::mutex | mutex_ |
double | planner_window_x_ |
double | planner_window_y_ |
std::string | tf_prefix_ |
Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap.
Definition at line 57 of file navfn_ros.h.
navfn::NavfnROS::NavfnROS | ( | ) |
Default constructor for the NavFnROS object.
Definition at line 41 of file navfn_ros.cpp.
navfn::NavfnROS::NavfnROS | ( | std::string | name, | |
costmap_2d::Costmap2DROS * | costmap_ros | |||
) |
Constructor for the NavFnROS object.
name | The name of this planner | |
costmap_ros | A pointer to the ROS wrapper of the costmap to use |
Definition at line 44 of file navfn_ros.cpp.
navfn::NavfnROS::~NavfnROS | ( | ) | [inline] |
Definition at line 141 of file navfn_ros.h.
void navfn::NavfnROS::clearRobotCell | ( | const tf::Stamped< tf::Pose > & | global_pose, | |
unsigned int | mx, | |||
unsigned int | my | |||
) | [private] |
Definition at line 175 of file navfn_ros.cpp.
bool navfn::NavfnROS::computePotential | ( | const geometry_msgs::Point & | world_point | ) |
Computes the full navigation function for the map given a point in the world to start from.
world_point | The point to use for seeding the navigation function |
Definition at line 144 of file navfn_ros.cpp.
void navfn::NavfnROS::getCostmap | ( | costmap_2d::Costmap2D & | costmap | ) | [protected, virtual] |
Store a copy of the current costmap in costmap. Called by makePlan.
Definition at line 194 of file navfn_ros.cpp.
bool navfn::NavfnROS::getPlanFromPotential | ( | const geometry_msgs::PoseStamped & | goal, | |
std::vector< geometry_msgs::PoseStamped > & | plan | |||
) |
Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first).
goal | The goal pose to create a plan to | |
plan | The plan... filled by the planner |
Definition at line 406 of file navfn_ros.cpp.
double navfn::NavfnROS::getPointPotential | ( | const geometry_msgs::Point & | world_point | ) |
Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first).
world_point | The point to get the potential for |
Definition at line 130 of file navfn_ros.cpp.
void navfn::NavfnROS::initialize | ( | std::string | name, | |
costmap_2d::Costmap2DROS * | costmap_ros | |||
) |
Initialization function for the NavFnROS object.
name | The name of this planner | |
costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Definition at line 50 of file navfn_ros.cpp.
bool navfn::NavfnROS::makePlan | ( | const geometry_msgs::PoseStamped & | start, | |
const geometry_msgs::PoseStamped & | goal, | |||
double | tolerance, | |||
std::vector< geometry_msgs::PoseStamped > & | plan | |||
) |
Given a goal pose in the world, compute a plan.
start | The start pose | |
goal | The goal pose | |
tolerance | The tolerance on the goal point for the planner | |
plan | The plan... filled by the planner |
Definition at line 241 of file navfn_ros.cpp.
bool navfn::NavfnROS::makePlan | ( | const geometry_msgs::PoseStamped & | start, | |
const geometry_msgs::PoseStamped & | goal, | |||
std::vector< geometry_msgs::PoseStamped > & | plan | |||
) |
Given a goal pose in the world, compute a plan.
start | The start pose | |
goal | The goal pose | |
plan | The plan... filled by the planner |
Definition at line 236 of file navfn_ros.cpp.
bool navfn::NavfnROS::makePlanService | ( | nav_msgs::GetPlan::Request & | req, | |
nav_msgs::GetPlan::Response & | resp | |||
) |
Definition at line 222 of file navfn_ros.cpp.
void navfn::NavfnROS::mapToWorld | ( | double | mx, | |
double | my, | |||
double & | wx, | |||
double & | wy | |||
) | [private] |
Definition at line 231 of file navfn_ros.cpp.
void navfn::NavfnROS::publishPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | path, | |
double | r, | |||
double | g, | |||
double | b, | |||
double | a | |||
) |
Publish a path for visualization purposes.
Definition at line 382 of file navfn_ros.cpp.
double navfn::NavfnROS::sq_distance | ( | const geometry_msgs::PoseStamped & | p1, | |
const geometry_msgs::PoseStamped & | p2 | |||
) | [inline, private] |
Definition at line 160 of file navfn_ros.h.
bool navfn::NavfnROS::validPointPotential | ( | const geometry_msgs::Point & | world_point, | |
double | tolerance | |||
) |
Check for a valid potential value at a given point in the world (Note: You should call computePotential first).
world_point | The point to get the potential for | |
tolerance | The tolerance on searching around the world_point specified |
Definition at line 103 of file navfn_ros.cpp.
bool navfn::NavfnROS::validPointPotential | ( | const geometry_msgs::Point & | world_point | ) |
Check for a valid potential value at a given point in the world (Note: You should call computePotential first).
world_point | The point to get the potential for |
Definition at line 99 of file navfn_ros.cpp.
bool navfn::NavfnROS::allow_unknown_ [protected] |
Definition at line 156 of file navfn_ros.h.
double navfn::NavfnROS::circumscribed_radius_ [protected] |
Definition at line 153 of file navfn_ros.h.
costmap_2d::Costmap2D navfn::NavfnROS::costmap_ [private] |
Definition at line 168 of file navfn_ros.h.
costmap_2d::Costmap2DPublisher* navfn::NavfnROS::costmap_publisher_ [private] |
Definition at line 170 of file navfn_ros.h.
costmap_2d::Costmap2DROS* navfn::NavfnROS::costmap_ros_ [protected] |
Definition at line 151 of file navfn_ros.h.
double navfn::NavfnROS::default_tolerance_ [private] |
Definition at line 169 of file navfn_ros.h.
double navfn::NavfnROS::inflation_radius_ [protected] |
Definition at line 153 of file navfn_ros.h.
bool navfn::NavfnROS::initialized_ [protected] |
Definition at line 156 of file navfn_ros.h.
double navfn::NavfnROS::inscribed_radius_ [protected] |
Definition at line 153 of file navfn_ros.h.
ros::ServiceServer navfn::NavfnROS::make_plan_srv_ [private] |
Definition at line 173 of file navfn_ros.h.
boost::mutex navfn::NavfnROS::mutex_ [private] |
Definition at line 172 of file navfn_ros.h.
ros::Publisher navfn::NavfnROS::plan_pub_ [protected] |
Definition at line 154 of file navfn_ros.h.
boost::shared_ptr<NavFn> navfn::NavfnROS::planner_ [protected] |
Definition at line 152 of file navfn_ros.h.
double navfn::NavfnROS::planner_window_x_ [private] |
Definition at line 169 of file navfn_ros.h.
double navfn::NavfnROS::planner_window_y_ [private] |
Definition at line 169 of file navfn_ros.h.
pcl_ros::Publisher<PotarrPoint> navfn::NavfnROS::potarr_pub_ [protected] |
Definition at line 155 of file navfn_ros.h.
std::string navfn::NavfnROS::tf_prefix_ [private] |
Definition at line 171 of file navfn_ros.h.
bool navfn::NavfnROS::visualize_potential_ [protected] |
Definition at line 156 of file navfn_ros.h.