goal_functions.h File Reference

#include <ros/ros.h>
#include "ros/time.h"
#include "ros/console.h"
#include "ros/assert.h"
#include "ros/common.h"
#include "ros/types.h"
#include "ros/forwards.h"
#include "ros/message.h"
#include "ros/serialization.h"
#include <boost/bind.hpp>
#include <typeinfo>
#include <boost/type_traits/is_void.hpp>
#include <boost/type_traits/is_base_of.hpp>
#include <boost/type_traits/is_const.hpp>
#include <boost/type_traits/add_const.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/utility/enable_if.hpp>
#include <boost/function.hpp>
#include <boost/make_shared.hpp>
#include <ros/static_assert.h>
#include <boost/type_traits/remove_reference.hpp>
#include "ros/message_traits.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_event.h"
#include "forwards.h"
#include "timer_options.h"
#include "wall_timer_options.h"
#include "ros/service_traits.h"
#include <boost/lexical_cast.hpp>
#include "subscription_callback_helper.h"
#include <boost/shared_ptr.hpp>
#include "ros/spinner.h"
#include <map>
#include <string>
#include <vector>
#include <time.h>
#include "ros/publisher.h"
#include <boost/utility.hpp>
#include "ros/service_server.h"
#include "ros/subscriber.h"
#include "ros/node_handle.h"
#include "ros/init.h"
#include "XmlRpcValue.h"
#include "node_handle.h"
#include "ros/names.h"
#include "sensor_msgs/PointCloud.h"
#include <ostream>
#include "ros/message_operations.h"
#include "std_msgs/Header.h"
#include <iostream>
#include <iomanip>
#include <cmath>
#include <sstream>
#include <stdexcept>
#include <list>
#include <boost/thread/mutex.hpp>
#include "geometry_msgs/Point.h"
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/TransformStamped.h"
#include "btMatrix3x3.h"
#include "tf/exceptions.h"
#include "LinearMath/btTransform.h"
#include <boost/signals.hpp>
#include "ros/ros.h"
#include <boost/thread/shared_mutex.hpp>
#include <boost/thread/condition_variable.hpp>
#include <boost/thread/tss.hpp>
#include <deque>
#include "boost/thread.hpp"
#include <tf/transform_datatypes.h>
#include "geometry_msgs/Pose.h"
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/PoseStamped.h"
#include <tf/transform_listener.h>
#include <algorithm>
#include <stdio.h>
#include <costmap_2d/costmap_2d.h>
#include "XmlRpcDispatch.h"
#include "XmlRpcSource.h"
#include <costmap_2d/observation.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <sensor_msgs/PointField.h>
#include "pcl/ros/point_traits.h"
#include <boost/mpl/is_sequence.hpp>
#include <boost/mpl/begin_end.hpp>
#include <boost/mpl/next_prior.hpp>
#include <boost/mpl/deref.hpp>
#include <boost/mpl/assert.hpp>
#include <boost/mpl/aux_/unwrap.hpp>
#include <boost/type_traits/is_same.hpp>
#include "pcl/exceptions.h"
#include <boost/foreach.hpp>
#include <queue>
#include <costmap_2d/cell_data.h>
#include <costmap_2d/cost_values.h>
#include <string.h>
#include <stdlib.h>
#include <stdint.h>
#include <math.h>
#include <limits.h>
#include "geometry_msgs/Point32.h"
#include <costmap_2d/VoxelGrid.h>
#include <tf/tfMessage.h>
#include <boost/weak_ptr.hpp>
#include <ros/callback_queue.h>
#include <boost/signals/connection.hpp>
#include <boost/noncopyable.hpp>
#include "connection.h"
#include "signal1.h"
#include <ros/subscription_callback_helper.h>
#include "simple_filter.h"
#include "boost/numeric/ublas/matrix.hpp"
#include "tf/tf.h"
#include "sensor_msgs/LaserScan.h"
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  base_local_planner

Functions

double base_local_planner::distance (double x1, double y1, double x2, double y2)
 Compute the distance between two points.
bool base_local_planner::goalOrientationReached (const tf::Stamped< tf::Pose > &global_pose, double goal_th, double yaw_goal_tolerance)
 Check if the goal orientation has been achieved.
bool base_local_planner::goalPositionReached (const tf::Stamped< tf::Pose > &global_pose, double goal_x, double goal_y, double xy_goal_tolerance)
 Check if the goal position has been achieved.
bool base_local_planner::isGoalReached (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap_ros, const std::string &global_frame, const nav_msgs::Odometry &base_odom, double rot_stopped_vel, double trans_stopped_vel, double xy_goal_tolerance, double yaw_goal_tolerance)
 Check if the goal pose has been achieved.
void base_local_planner::prunePlan (const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 Trim off parts of the global plan that are far enough behind the robot.
void base_local_planner::publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub, double r, double g, double b, double a)
 Publish a plan for visualization purposes.
bool base_local_planner::stopped (const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
 Check whether the robot is stopped or not.
bool base_local_planner::transformGlobalPlan (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
 Transforms the global plan of the robot from the planner frame to the local frame.
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Fri Jan 11 09:41:51 2013