-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgrid_layer.h
36 lines (33 loc) · 1.2 KB
/
grid_layer.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
#ifndef GRID_LAYER_H_
#define GRID_LAYER_H_
#include <ros/ros.h>
#include <costmap_2d/layer.h>
#include <costmap_2d/layered_costmap.h>
#include <costmap_2d/GenericPluginConfig.h>
#include <dynamic_reconfigure/server.h>
#include "geometry_msgs/Polygon.h"
namespace simple_layer_namespace{
class GridLayer : public costmap_2d::Layer, public costmap_2d::Costmap2D{
public:
GridLayer();
bool rolling_window_;
virtual void onInitialize();
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x,
double* max_y);
virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
bool isDiscretized()
{
return true;
}
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("polygonPublisher", 1000, &GridLayer::msgSub, this);
std::vector<float> xs;
std::vector<float> ys;
virtual void msgSub(const geometry_msgs::Polygon::ConstPtr& msg);
virtual void matchSize();
private:
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *dsrv_;
};
}
#endif