37 #ifndef TRAJECTORY_ROLLOUT_WORLD_MODEL_H_ 38 #define TRAJECTORY_ROLLOUT_WORLD_MODEL_H_ 43 #include <geometry_msgs/Point.h> 65 virtual double footprintCost(
const geometry_msgs::Point& position,
const std::vector<geometry_msgs::Point>& footprint,
66 double inscribed_radius,
double circumscribed_radius) = 0;
68 double footprintCost(
double x,
double y,
double theta,
const std::vector<geometry_msgs::Point>& footprint_spec,
double inscribed_radius = 0.0,
double circumscribed_radius=0.0){
70 double cos_th =
cos(theta);
71 double sin_th =
sin(theta);
72 std::vector<geometry_msgs::Point> oriented_footprint;
73 for(
unsigned int i = 0; i < footprint_spec.size(); ++i){
74 geometry_msgs::Point new_pt;
75 new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
76 new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
77 oriented_footprint.push_back(new_pt);
80 geometry_msgs::Point robot_position;
84 if(inscribed_radius==0.0){
88 return footprintCost(robot_position, oriented_footprint, inscribed_radius, circumscribed_radius);
99 double footprintCost(
const geometry_msgs::Point& position,
const std::vector<geometry_msgs::Point>& footprint,
100 double inscribed_radius,
double circumscribed_radius,
double extra) {
101 return footprintCost(position, footprint, inscribed_radius, circumscribed_radius);
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
double footprintCost(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0)
double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius, double extra)
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid...
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
virtual ~WorldModel()
Subclass will implement a destructor.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)