Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
iri_bspline_navfn::NavfnROS Class Reference

Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap. More...

#include <navfn_ros.h>

Inheritance diagram for iri_bspline_navfn::NavfnROS:
Inheritance graph
[legend]

List of all members.

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, 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, double tolerance, 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 ()
 Default constructor for the NavFnROS object.
 NavfnROS (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 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)
 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, double tolerance)
 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::Costmap2DROScostmap_ros_
double inflation_radius_
bool initialized_
double inscribed_radius_
ros::Publisher plan_pub_
boost::shared_ptr< NavFnplanner_
pcl_ros::Publisher< PotarrPointpotarr_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::Costmap2DPublishercostmap_publisher_
double default_tolerance_
ros::ServiceServer make_plan_srv_
boost::mutex mutex_
double planner_window_x_
double planner_window_y_
std::string tf_prefix_

Detailed Description

Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap.

Definition at line 58 of file navfn_ros.h.


Constructor & Destructor Documentation

Default constructor for the NavFnROS object.

Definition at line 45 of file navfn_ros.cpp.

iri_bspline_navfn::NavfnROS::NavfnROS ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Constructor for the NavFnROS object.

Parameters:
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use

Definition at line 48 of file navfn_ros.cpp.

Definition at line 142 of file navfn_ros.h.


Member Function Documentation

void iri_bspline_navfn::NavfnROS::clearRobotCell ( const tf::Stamped< tf::Pose > &  global_pose,
unsigned int  mx,
unsigned int  my 
) [private]

Definition at line 179 of file navfn_ros.cpp.

Computes the full navigation function for the map given a point in the world to start from.

Parameters:
world_pointThe point to use for seeding the navigation function
Returns:
True if the navigation function was computed successfully, false otherwise

Definition at line 148 of file navfn_ros.cpp.

void iri_bspline_navfn::NavfnROS::getCostmap ( costmap_2d::Costmap2D costmap) [protected, virtual]

Store a copy of the current costmap in costmap. Called by makePlan.

Definition at line 198 of file navfn_ros.cpp.

bool iri_bspline_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)

Parameters:
goalThe goal pose to create a plan to
planThe plan... filled by the planner
Returns:
True if a valid plan was found, false otherwise

Definition at line 419 of file navfn_ros.cpp.

Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first)

Parameters:
world_pointThe point to get the potential for
Returns:
The navigation function's value at that point in the world

Definition at line 134 of file navfn_ros.cpp.

void iri_bspline_navfn::NavfnROS::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Initialization function for the NavFnROS object.

Parameters:
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning

Implements nav_core::BaseGlobalPlanner.

Definition at line 54 of file navfn_ros.cpp.

bool iri_bspline_navfn::NavfnROS::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
) [virtual]

Given a goal pose in the world, compute a plan.

Parameters:
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
Returns:
True if a valid plan was found, false otherwise

Implements nav_core::BaseGlobalPlanner.

Definition at line 240 of file navfn_ros.cpp.

bool iri_bspline_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.

Parameters:
startThe start pose
goalThe goal pose
toleranceThe tolerance on the goal point for the planner
planThe plan... filled by the planner
Returns:
True if a valid plan was found, false otherwise

Definition at line 245 of file navfn_ros.cpp.

bool iri_bspline_navfn::NavfnROS::makePlanService ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  resp 
)

Definition at line 226 of file navfn_ros.cpp.

void iri_bspline_navfn::NavfnROS::mapToWorld ( double  mx,
double  my,
double &  wx,
double &  wy 
) [private]

Definition at line 235 of file navfn_ros.cpp.

void iri_bspline_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 395 of file navfn_ros.cpp.

double iri_bspline_navfn::NavfnROS::sq_distance ( const geometry_msgs::PoseStamped &  p1,
const geometry_msgs::PoseStamped &  p2 
) [inline, private]

Definition at line 161 of file navfn_ros.h.

Check for a valid potential value at a given point in the world (Note: You should call computePotential first)

Parameters:
world_pointThe point to get the potential for
Returns:
True if the navigation function is valid at that point in the world, false otherwise

Definition at line 103 of file navfn_ros.cpp.

bool iri_bspline_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)

Parameters:
world_pointThe point to get the potential for
toleranceThe tolerance on searching around the world_point specified
Returns:
True if the navigation function is valid at that point in the world, false otherwise

Definition at line 107 of file navfn_ros.cpp.


Member Data Documentation

Definition at line 157 of file navfn_ros.h.

Definition at line 154 of file navfn_ros.h.

Definition at line 169 of file navfn_ros.h.

Definition at line 171 of file navfn_ros.h.

Definition at line 152 of file navfn_ros.h.

Definition at line 170 of file navfn_ros.h.

Definition at line 154 of file navfn_ros.h.

Definition at line 157 of file navfn_ros.h.

Definition at line 154 of file navfn_ros.h.

Definition at line 174 of file navfn_ros.h.

boost::mutex iri_bspline_navfn::NavfnROS::mutex_ [private]

Definition at line 173 of file navfn_ros.h.

Definition at line 155 of file navfn_ros.h.

boost::shared_ptr<NavFn> iri_bspline_navfn::NavfnROS::planner_ [protected]

Definition at line 153 of file navfn_ros.h.

Definition at line 170 of file navfn_ros.h.

Definition at line 170 of file navfn_ros.h.

Definition at line 156 of file navfn_ros.h.

Definition at line 172 of file navfn_ros.h.

Definition at line 157 of file navfn_ros.h.


The documentation for this class was generated from the following files:


iri_bspline_navfn
Author(s): Maintained by IRI Robotics Lab
autogenerated on Fri Dec 6 2013 23:43:15