38 #ifndef EBAND_CONVERSIONS_AND_TYPES_H_ 39 #define EBAND_CONVERSIONS_AND_TYPES_H_ 44 #include <geometry_msgs/PoseStamped.h> 45 #include <geometry_msgs/Pose.h> 46 #include <geometry_msgs/Pose2D.h> 79 void PoseToPose2D(
const geometry_msgs::Pose pose, geometry_msgs::Pose2D& pose2D);
87 void Pose2DToPose(geometry_msgs::Pose& pose,
const geometry_msgs::Pose2D pose2D);
101 std::vector<geometry_msgs::PoseStamped>& transformed_plan, std::vector<int>& start_end_counts_from_end);
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 t...
double getCircumscribedRadius(costmap_2d::Costmap2DROS &costmap)
Gets the footprint of the robot and computes the circumscribed radius for the eband approach...
geometry_msgs::PoseStamped center
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.
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...