Namespaces | Classes | Typedefs | Functions
iri_ackermann_local_planner Namespace Reference

Namespaces

namespace  msg

Classes

class  CostmapModel
 A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using the costmap. More...
class  MapCell
 Stores path distance and goal distance information used for scoring trajectories. More...
class  MapGrid
 A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller. More...
struct  MapGridCostPoint
class  MapGridVisualizer
class  PlanarLaserScan
 Stores a scan from a planar laser that can be used to clear freespace. More...
class  PointGrid
 A class that implements the WorldModel interface to provide free-space collision checks for the trajectory controller. This class stores points binned into a grid and performs point-in-polygon checks when necessary to determine the legality of a footprint at a given position/orientation. More...
struct  Position2DInt_
class  Trajectory
 Holds a trajectory generated by an x, y, and theta velocity. More...
class  TrajectoryPlanner
 Computes control velocities for a robot given a costmap, a plan, and the robot's position in the world. More...
class  TrajectoryPlannerROS
 A ROS wrapper for the trajectory controller that queries the param server to construct a controller. More...
class  VoxelGridModel
 A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using a 3D voxel grid. More...
class  WorldModel
 An interface the trajectory controller uses to interact with the world regardless of the underlying world model. More...

Typedefs

typedef
::iri_ackermann_local_planner::Position2DInt_
< std::allocator< void > > 
Position2DInt
typedef boost::shared_ptr
< ::iri_ackermann_local_planner::Position2DInt
const > 
Position2DIntConstPtr
typedef boost::shared_ptr
< ::iri_ackermann_local_planner::Position2DInt
Position2DIntPtr

Functions

double distance (double x1, double y1, double x2, double y2)
 Compute the distance between two points.
bool goalOrientationReached (const tf::Stamped< tf::Pose > &global_pose, double goal_th, double yaw_goal_tolerance)
 Check if the goal orientation has been achieved.
bool goalPositionReached (const tf::Stamped< tf::Pose > &global_pose, double goal_x, double goal_y, double xy_goal_tolerance)
 Check if the goal position has been achieved.
bool isGoalReached (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap_ros, const std::string &global_frame, const nav_msgs::Odometry &base_odom, double rot_stopped_vel, double trans_stopped_vel, double xy_goal_tolerance, double yaw_goal_tolerance)
 Check if the goal pose has been achieved.
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::iri_ackermann_local_planner::Position2DInt_< ContainerAllocator > &v)
void prunePlan (const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 Trim off parts of the global plan that are far enough behind the robot.
void publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub, double r, double g, double b, double a)
 Publish a plan for visualization purposes.
bool stopped (const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
 Check whether the robot is stopped or not.
bool transformGlobalPlan (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
 Transforms the global plan of the robot from the planner frame to the local frame.

Typedef Documentation

Definition at line 47 of file Position2DInt.h.

Definition at line 50 of file Position2DInt.h.

Definition at line 49 of file Position2DInt.h.


Function Documentation

double iri_ackermann_local_planner::distance ( double  x1,
double  y1,
double  x2,
double  y2 
)

Compute the distance between two points.

Parameters:
x1The first x point
y1The first y point
x2The second x point
y2The second y point

Definition at line 40 of file goal_functions.cpp.

bool iri_ackermann_local_planner::goalOrientationReached ( const tf::Stamped< tf::Pose > &  global_pose,
double  goal_th,
double  yaw_goal_tolerance 
)

Check if the goal orientation has been achieved.

Parameters:
global_poseThe pose of the robot in the global frame
goal_xThe desired x value for the goal
goal_yThe desired y value for the goal
yaw_goal_toleranceThe tolerance on the position
Returns:
True if achieved, false otherwise

Definition at line 49 of file goal_functions.cpp.

bool iri_ackermann_local_planner::goalPositionReached ( const tf::Stamped< tf::Pose > &  global_pose,
double  goal_x,
double  goal_y,
double  xy_goal_tolerance 
)

Check if the goal position has been achieved.

Parameters:
global_poseThe pose of the robot in the global frame
goal_xThe desired x value for the goal
goal_yThe desired y value for the goal
xy_goal_toleranceThe tolerance on the position
Returns:
True if achieved, false otherwise

Definition at line 44 of file goal_functions.cpp.

bool iri_ackermann_local_planner::isGoalReached ( const tf::TransformListener tf,
const std::vector< geometry_msgs::PoseStamped > &  global_plan,
const costmap_2d::Costmap2DROS costmap_ros,
const std::string &  global_frame,
const nav_msgs::Odometry &  base_odom,
double  rot_stopped_vel,
double  trans_stopped_vel,
double  xy_goal_tolerance,
double  yaw_goal_tolerance 
)

Check if the goal pose has been achieved.

Parameters:
tfA reference to a transform listener
global_planThe plan being followed
costmap_rosA reference to the costmap object being used by the planner
global_frameThe global frame of the local planner
base_odomThe current odometry information for the robot
rot_stopped_velThe rotational velocity below which the robot is considered stopped
trans_stopped_velThe translational velocity below which the robot is considered stopped
xy_goal_toleranceThe translational tolerance on reaching the goal
yaw_goal_toleranceThe rotational tolerance on reaching the goal
Returns:
True if achieved, false otherwise

Definition at line 177 of file goal_functions.cpp.

template<typename ContainerAllocator >
std::ostream& iri_ackermann_local_planner::operator<< ( std::ostream &  s,
const ::iri_ackermann_local_planner::Position2DInt_< ContainerAllocator > &  v 
)

Definition at line 54 of file Position2DInt.h.

void iri_ackermann_local_planner::prunePlan ( const tf::Stamped< tf::Pose > &  global_pose,
std::vector< geometry_msgs::PoseStamped > &  plan,
std::vector< geometry_msgs::PoseStamped > &  global_plan 
)

Trim off parts of the global plan that are far enough behind the robot.

Parameters:
global_poseThe pose of the robot in the global frame
planThe plan to be pruned
global_planThe plan to be pruned in the frame of the planner

Definition at line 73 of file goal_functions.cpp.

void iri_ackermann_local_planner::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path,
const ros::Publisher pub,
double  r,
double  g,
double  b,
double  a 
)

Publish a plan for visualization purposes.

Parameters:
pathThe plan to publish
pubThe published to use
r,g,b,aThe color and alpha value to use when publishing

Definition at line 54 of file goal_functions.cpp.

bool iri_ackermann_local_planner::stopped ( const nav_msgs::Odometry &  base_odom,
const double &  rot_stopped_velocity,
const double &  trans_stopped_velocity 
)

Check whether the robot is stopped or not.

Parameters:
base_odomThe current odometry information for the robot
rot_stopped_velocityThe rotational velocity below which the robot is considered stopped
trans_stopped_velocityThe translational velocity below which the robot is considered stopped
Returns:
True if the robot is stopped, false otherwise

Definition at line 243 of file goal_functions.cpp.

bool iri_ackermann_local_planner::transformGlobalPlan ( const tf::TransformListener tf,
const std::vector< geometry_msgs::PoseStamped > &  global_plan,
const costmap_2d::Costmap2DROS costmap,
const std::string &  global_frame,
std::vector< geometry_msgs::PoseStamped > &  transformed_plan 
)

Transforms the global plan of the robot from the planner frame to the local frame.

Parameters:
tfA reference to a transform listener
global_planThe plan to be transformed
costmapA reference to the costmap being used so the window size for transforming can be computed
global_frameThe frame to transform the plan to
transformed_planPopulated with the transformed plan

Definition at line 92 of file goal_functions.cpp.



iri_ackermann_local_planner
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 23:50:18