Namespaces | |
namespace | msg |
namespace | srv |
Classes | |
struct | change_max_vel |
struct | change_max_velRequest_ |
struct | change_max_velResponse_ |
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_diff_local_planner::change_max_velRequest_ < std::allocator< void > > | change_max_velRequest |
typedef boost::shared_ptr < ::iri_diff_local_planner::change_max_velRequest const > | change_max_velRequestConstPtr |
typedef boost::shared_ptr < ::iri_diff_local_planner::change_max_velRequest > | change_max_velRequestPtr |
typedef ::iri_diff_local_planner::change_max_velResponse_ < std::allocator< void > > | change_max_velResponse |
typedef boost::shared_ptr < ::iri_diff_local_planner::change_max_velResponse const > | change_max_velResponseConstPtr |
typedef boost::shared_ptr < ::iri_diff_local_planner::change_max_velResponse > | change_max_velResponsePtr |
typedef ::iri_diff_local_planner::Position2DInt_ < std::allocator< void > > | Position2DInt |
typedef boost::shared_ptr < ::iri_diff_local_planner::Position2DInt const > | Position2DIntConstPtr |
typedef boost::shared_ptr < ::iri_diff_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, bool xy_tolerance_latch_) |
Check if the goal pose has been achieved. | |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::iri_diff_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 ::iri_diff_local_planner::change_max_velRequest_<std::allocator<void> > iri_diff_local_planner::change_max_velRequest |
Definition at line 46 of file change_max_vel.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::change_max_velRequest const> iri_diff_local_planner::change_max_velRequestConstPtr |
Definition at line 49 of file change_max_vel.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::change_max_velRequest> iri_diff_local_planner::change_max_velRequestPtr |
Definition at line 48 of file change_max_vel.h.
typedef ::iri_diff_local_planner::change_max_velResponse_<std::allocator<void> > iri_diff_local_planner::change_max_velResponse |
Definition at line 69 of file change_max_vel.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::change_max_velResponse const> iri_diff_local_planner::change_max_velResponseConstPtr |
Definition at line 72 of file change_max_vel.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::change_max_velResponse> iri_diff_local_planner::change_max_velResponsePtr |
Definition at line 71 of file change_max_vel.h.
typedef ::iri_diff_local_planner::Position2DInt_<std::allocator<void> > iri_diff_local_planner::Position2DInt |
Definition at line 47 of file Position2DInt.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::Position2DInt const> iri_diff_local_planner::Position2DIntConstPtr |
Definition at line 50 of file Position2DInt.h.
typedef boost::shared_ptr< ::iri_diff_local_planner::Position2DInt> iri_diff_local_planner::Position2DIntPtr |
Definition at line 49 of file Position2DInt.h.
double iri_diff_local_planner::distance | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) |
Compute the distance between two points.
x1 | The first x point |
y1 | The first y point |
x2 | The second x point |
y2 | The second y point |
Definition at line 40 of file goal_functions.cpp.
bool iri_diff_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.
global_pose | The pose of the robot in the global frame |
goal_x | The desired x value for the goal |
goal_y | The desired y value for the goal |
yaw_goal_tolerance | The tolerance on the position |
Definition at line 49 of file goal_functions.cpp.
bool iri_diff_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.
global_pose | The pose of the robot in the global frame |
goal_x | The desired x value for the goal |
goal_y | The desired y value for the goal |
xy_goal_tolerance | The tolerance on the position |
Definition at line 44 of file goal_functions.cpp.
bool iri_diff_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, | ||
bool | xy_tolerance_latch_ | ||
) |
Check if the goal pose has been achieved.
tf | A reference to a transform listener |
global_plan | The plan being followed |
costmap_ros | A reference to the costmap object being used by the planner |
global_frame | The global frame of the local planner |
base_odom | The current odometry information for the robot |
rot_stopped_vel | The rotational velocity below which the robot is considered stopped |
trans_stopped_vel | The translational velocity below which the robot is considered stopped |
xy_goal_tolerance | The translational tolerance on reaching the goal |
yaw_goal_tolerance | The rotational tolerance on reaching the goal |
Definition at line 177 of file goal_functions.cpp.
std::ostream& iri_diff_local_planner::operator<< | ( | std::ostream & | s, |
const ::iri_diff_local_planner::Position2DInt_< ContainerAllocator > & | v | ||
) |
Definition at line 54 of file Position2DInt.h.
void iri_diff_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.
global_pose | The pose of the robot in the global frame |
plan | The plan to be pruned |
global_plan | The plan to be pruned in the frame of the planner |
Definition at line 73 of file goal_functions.cpp.
void iri_diff_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.
path | The plan to publish |
pub | The published to use |
r,g,b,a | The color and alpha value to use when publishing |
Definition at line 54 of file goal_functions.cpp.
bool iri_diff_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.
base_odom | The current odometry information for the robot |
rot_stopped_velocity | The rotational velocity below which the robot is considered stopped |
trans_stopped_velocity | The translational velocity below which the robot is considered stopped |
Definition at line 243 of file goal_functions.cpp.
bool iri_diff_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.
tf | A reference to a transform listener |
global_plan | The plan to be transformed |
costmap | A reference to the costmap being used so the window size for transforming can be computed |
global_frame | The frame to transform the plan to |
transformed_plan | Populated with the transformed plan |
Definition at line 92 of file goal_functions.cpp.