56 StaticLayer::StaticLayer() : dsrv_(
NULL) {}
71 std::string map_topic;
72 nh.param(
"map_topic", map_topic, std::string(
"map"));
78 int temp_lethal_threshold, temp_unknown_cost_value;
79 nh.param(
"lethal_cost_threshold", temp_lethal_threshold,
int(100));
80 nh.param(
"unknown_cost_value", temp_unknown_cost_value,
int(-1));
111 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
112 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(
114 dsrv_->setCallback(cb);
132 resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
133 master->getOriginX(), master->getOriginY());
140 return NO_INFORMATION;
142 return LETHAL_OBSTACLE;
147 return scale * LETHAL_OBSTACLE;
152 unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
154 ROS_DEBUG(
"Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
158 if (master->getSizeInCellsX() != size_x ||
159 master->getSizeInCellsY() != size_y ||
160 master->getResolution() != new_map->info.resolution ||
161 master->getOriginX() != new_map->info.origin.position.x ||
162 master->getOriginY() != new_map->info.origin.position.y ||
165 ROS_INFO(
"Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
167 new_map->info.origin.position.y,
true);
170 origin_x_ != new_map->info.origin.position.x ||
171 origin_y_ != new_map->info.origin.position.y){
175 unsigned int index = 0;
178 for (
unsigned int i = 0; i < size_y; ++i)
180 for (
unsigned int j = 0; j < size_x; ++j)
182 unsigned char value = new_map->data[index];
199 for (
unsigned int y = 0; y < update->height ; y++)
201 unsigned int index_base = (update->y + y) *
size_x_;
202 for (
unsigned int x = 0; x < update->width ; x++)
204 unsigned int index = index_base + x + update->x;
236 double* max_x,
double* max_y)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
bool subscribe_to_updates_
LayeredCostmap * layered_costmap_
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
bool track_unknown_space_
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
std::string getGlobalFrameID() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
ros::Subscriber map_update_sub_
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
unsigned char unknown_cost_value_
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
unsigned char interpretValue(unsigned char value)
std::string global_frame_
The global frame for the costmap.
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
unsigned int getSizeInCellsY() const
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
unsigned int getSizeInCellsX() const
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
virtual void onInitialize()
double getResolution() const
void updateMap(double robot_x, double robot_y, double robot_yaw)
ROSCPP_DECL void spinOnce()
unsigned char lethal_threshold_
virtual void deactivate()