Classes | Enumerations | Functions
eband_local_planner Namespace Reference

Classes

struct  Bubble
 < More...
class  EBandPlanner
 Implements the Elastic Band Method for SE2-Manifold (mobile Base) More...
class  EBandPlannerROS
 Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method. More...
class  EBandTrajectoryCtrl
class  EBandVisualization

Enumerations

enum  AddAtPosition { add_front, add_back }

Functions

double angularDiff (const geometry_msgs::Twist &heading, const geometry_msgs::Pose &pose)
double getCircumscribedRadius (costmap_2d::Costmap2DROS &costmap)
 Gets the footprint of the robot and computes the circumscribed radius for the eband approach.
void Pose2DToPose (geometry_msgs::Pose &pose, const geometry_msgs::Pose2D pose2D)
 Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from euler angles to quaternions, -> z-coordinate is set to zero)
void PoseToPose2D (const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose2D)
 Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from quaternions to euler angles)
bool transformGlobalPlan (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan, std::vector< int > &start_end_counts_from_end)
 Transforms the global plan of the robot from the planner frame to the local frame. This replaces the transformGlobalPlan as defined in the base_local_planner/goal_functions.h main difference is that it additionally outputs counter indicating which part of the plan has been transformed.

Enumeration Type Documentation

Enumerator:
add_front 
add_back 

Definition at line 70 of file conversions_and_types.h.


Function Documentation

double eband_local_planner::angularDiff ( const geometry_msgs::Twist &  heading,
const geometry_msgs::Pose pose 
)

Definition at line 161 of file eband_trajectory_controller.cpp.

Gets the footprint of the robot and computes the circumscribed radius for the eband approach.

Parameters:
costmapA reference to the costmap from which the radius is computed
Returns:
radius in meters

Definition at line 211 of file conversions_and_types.cpp.

void eband_local_planner::Pose2DToPose ( geometry_msgs::Pose pose,
const geometry_msgs::Pose2D  pose2D 
)

Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from euler angles to quaternions, -> z-coordinate is set to zero)

Parameters:
Referencesto converted ROS Pose2D frame
Pose2Dwhich shall be converted

Definition at line 66 of file conversions_and_types.cpp.

void eband_local_planner::PoseToPose2D ( const geometry_msgs::Pose  pose,
geometry_msgs::Pose2D &  pose2D 
)

Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from quaternions to euler angles)

Parameters:
Posewhich shall be converted
Referencesto converted ROS Pose2D frmae

Definition at line 42 of file conversions_and_types.cpp.

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

Transforms the global plan of the robot from the planner frame to the local frame. This replaces the transformGlobalPlan as defined in the base_local_planner/goal_functions.h main difference is that it additionally outputs counter indicating which part of the plan has been transformed.

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
numberof start and end frame counted from the end of the global plan

Definition at line 89 of file conversions_and_types.cpp.



eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Thu Jun 6 2019 18:50:52