|
void | swri_route_util::fillOrientations (marti_nav_msgs::Plan &path) |
|
bool | swri_route_util::findLocalNearestDistanceForward (const marti_nav_msgs::Plan &path, const double x, const double y, marti_nav_msgs::PlanPosition &nearest_position, double &nearest_separation) |
|
void | swri_route_util::getPathPose (const marti_nav_msgs::Plan &path, const marti_nav_msgs::PlanPosition position, tf::Transform &tf, const bool allow_extrapolation=false) |
|
void | swri_route_util::getPlanPosition (const marti_nav_msgs::Plan &path, const marti_nav_msgs::PlanPosition position, tf::Vector3 &tf, bool extrapolate=false) |
|
tf::Vector3 | swri_route_util::getPointPosition (const marti_nav_msgs::PlanPoint &pt) |
|
void | swri_route_util::interpolatePlanPosition (const marti_nav_msgs::Plan &path, const marti_nav_msgs::PlanPosition position, marti_nav_msgs::PlanPoint &pt, bool extrapolate=false) |
|
void | swri_route_util::normalizePlanPosition (marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &path) |
|
bool | swri_route_util::planDistance (double &distance, const marti_nav_msgs::PlanPosition &start, const marti_nav_msgs::PlanPosition &end, const marti_nav_msgs::Plan &route) |
|
bool | swri_route_util::projectOntoPlan (marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &route, const tf::Vector3 &point, bool extrapolate_before_start, bool extrapolate_past_end) |
|
bool | swri_route_util::projectOntoPlanWindow (marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &route, const tf::Vector3 &point, const marti_nav_msgs::PlanPosition &window_start, const marti_nav_msgs::PlanPosition &window_end) |
|
void | swri_route_util::projectToXY (marti_nav_msgs::Plan &route) |
|
void | swri_route_util::transform (marti_nav_msgs::Plan &path, const swri_transform_util::Transform &transform, const std::string &target_frame) |
|