Go to the documentation of this file.
69 std::string map_topic;
70 nh.param(
"map_topic", map_topic, std::string(
"map"));
77 int temp_lethal_threshold, temp_unknown_cost_value;
78 nh.param(
"lethal_cost_threshold", temp_lethal_threshold,
int(100));
79 nh.param(
"unknown_cost_value", temp_unknown_cost_value,
int(-1));
120 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
121 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb =
122 [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
123 dsrv_->setCallback(cb);
168 unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
170 ROS_DEBUG(
"Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
178 master->
getOriginX() != new_map->info.origin.position.x ||
179 master->
getOriginY() != new_map->info.origin.position.y))
182 ROS_INFO(
"Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
184 new_map->info.origin.position.y,
189 origin_x_ != new_map->info.origin.position.x ||
190 origin_y_ != new_map->info.origin.position.y)
193 ROS_INFO(
"Resizing static layer to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
194 resizeMap(size_x, size_y, new_map->info.resolution,
195 new_map->info.origin.position.x, new_map->info.origin.position.y);
198 unsigned int index = 0;
201 for (
unsigned int i = 0; i < size_y; ++i)
203 for (
unsigned int j = 0; j < size_x; ++j)
205 unsigned char value = new_map->data[index];
222 ROS_INFO(
"Shutting down the map subscriber. first_map_only flag is on");
230 for (
unsigned int y = 0; y <
update->height ; y++)
233 for (
unsigned int x = 0; x <
update->width ; x++)
235 unsigned int index = index_base + x +
update->x;
271 double* max_x,
double* max_y)
284 *min_x = std::min(wx, *min_x);
285 *min_y = std::min(wy, *min_y);
288 *max_x = std::max(wx, *max_x);
289 *max_y = std::max(wy, *max_y);
313 geometry_msgs::TransformStamped transform;
326 for (
unsigned int i = min_i; i < max_i; ++i)
328 for (
unsigned int j = min_j; j < max_j; ++j)
333 tf2::Vector3 p(wx, wy, 0);
unsigned char lethal_threshold_
void convert(const A &a, B &b)
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
bool subscribe_to_updates_
frame that map is located in
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
virtual void activate()
Restart publishers if they've been stopped.
static const unsigned char NO_INFORMATION
std::string getTopic() const
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
ROSCPP_DECL void spinOnce()
unsigned char interpretValue(unsigned char value)
A 2D costmap provides a mapping between points in the world and their associated "costs".
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
ros::Subscriber map_update_sub_
double getOriginX() const
Accessor for the x origin of the costmap.
LayeredCostmap * layered_costmap_
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
std::string global_frame_
The global frame for the costmap.
bool track_unknown_space_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
virtual void deactivate()
Stop publishers.
static const unsigned char LETHAL_OBSTACLE
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
bool first_map_only_
Store the first static map and reuse it on reinitializing.
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
double getOriginY() const
Accessor for the y origin of the costmap.
double getResolution() const
Accessor for the resolution of the costmap.
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
static const unsigned char FREE_SPACE
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
const std::string & getGlobalFrameID() const noexcept
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
unsigned char unknown_cost_value_
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17