#include <cmath>#include <angles/angles.h>#include <base_local_planner/goal_functions.h>#include <base_local_planner/line_iterator.h>#include <costmap_2d/footprint.h>#include <graceful_controller/graceful_controller.hpp>#include <graceful_controller_ros/orientation_tools.hpp>#include <std_msgs/Float32.h>#include "graceful_controller_ros/graceful_controller_ros.hpp"#include <pluginlib/class_list_macros.h>
Go to the source code of this file.
Namespaces | |
| graceful_controller | |
Functions | |
| void | graceful_controller::computeDistanceAlongPath (const std::vector< geometry_msgs::PoseStamped > &poses, std::vector< double > &distances) |
| Compute distance of poses along a path. Assumes poses are in robot-centric frame. More... | |
| bool | graceful_controller::isColliding (double x, double y, double theta, costmap_2d::Costmap2DROS *costmap, visualization_msgs::MarkerArray *viz, double inflation=1.0) |
| Collision check the robot pose. More... | |
| double | graceful_controller::sign (double x) |