Namespaces | Functions
path_ops.h File Reference
#include <nav_2d_msgs/Path2D.h>
Include dependency graph for path_ops.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 nav_2d_utils
 A set of utility functions for Bounds objects interacting with other messages/types.
 

Functions

void nav_2d_utils::addPose (nav_2d_msgs::Path2D &path, double x, double y, double theta=0.0)
 Convenience function to add a pose to a path in one line. More...
 
nav_2d_msgs::Path2D nav_2d_utils::adjustPlanResolution (const nav_2d_msgs::Path2D &global_plan_in, double resolution)
 Increase plan resolution to match that of the costmap by adding points linearly between points. More...
 
nav_2d_msgs::Path2D nav_2d_utils::compressPlan (const nav_2d_msgs::Path2D &input_path, double epsilon=0.1)
 Decrease the length of the plan by eliminating colinear points. More...
 
double nav_2d_utils::getPlanLength (const nav_2d_msgs::Path2D &plan, const unsigned int start_index=0)
 Calculate the length of the plan, starting from the given index. More...
 
double nav_2d_utils::getPlanLength (const nav_2d_msgs::Path2D &plan, const geometry_msgs::Pose2D &query_pose)
 Calculate the length of the plan from the pose on the plan closest to the given pose. More...
 
double nav_2d_utils::poseDistance (const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
 Calculate the linear distance between two poses. More...
 


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32