12 #include <nav_msgs/OccupancyGrid.h> 20 int main(
int argc,
char **argv) {
30 std::string image_resource_name =
"cost_map_ros/example.yaml";
31 std::shared_ptr<cost_map::LoadImageBundle> loader;
33 loader = std::make_shared<cost_map::LoadImageBundle>(image_resource_name);
37 float inscribed_radius = 0.3;
38 float inflation_radius = 0.8;
39 float inflation_exponential_rate = 5.0;
42 inflate(
"obstacle_costs",
"inflated_costs",
48 deflate(
"inflated_costs",
"deflated_costs", *(loader->cost_map));
49 }
catch (
const std::exception& e) {
50 std::cout << ecl::red <<
"[ERROR] " << e.what() << ecl::reset << std::endl;
57 ros::Publisher obstacle_publisher = nodehandle.
advertise<nav_msgs::OccupancyGrid>(
"obstacle_layer", 1, latched);
58 ros::Publisher inflation_publisher = nodehandle.
advertise<nav_msgs::OccupancyGrid>(
"inflation_layer", 1, latched);
59 ros::Publisher deflation_publisher = nodehandle.
advertise<nav_msgs::OccupancyGrid>(
"deflation_layer", 1, latched);
61 nav_msgs::OccupancyGrid obstacle_occupancy_grid_msg, inflated_occupancy_grid_msg, deflated_occupancy_grid_msg;
65 obstacle_publisher.
publish(obstacle_occupancy_grid_msg);
66 inflation_publisher.publish(inflated_occupancy_grid_msg);
67 deflation_publisher.publish(deflated_occupancy_grid_msg);
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void toOccupancyGrid(const cost_map::CostMap &cost_map, const std::string &layer, nav_msgs::OccupancyGrid &msg)
int main(int argc, char **argv)