inflations.cpp
Go to the documentation of this file.
00001 
00004 /*****************************************************************************
00005 ** Includes
00006 *****************************************************************************/
00007 
00008 #include <cost_map_ros/cost_map_ros.hpp>
00009 #include <ecl/console.hpp>
00010 #include <exception>
00011 #include <memory>
00012 #include <nav_msgs/OccupancyGrid.h>
00013 #include <ros/ros.h>
00014 #include <cstdlib>
00015 
00016 /*****************************************************************************
00017 ** Main
00018 *****************************************************************************/
00019 
00020 int main(int argc, char **argv) {
00021   /****************************************
00022   ** Ros
00023   ****************************************/
00024   ros::init(argc, argv, "inflations");
00025   ros::NodeHandle nodehandle("~");
00026 
00027   /****************************************
00028   ** Load
00029   ****************************************/
00030   std::string image_resource_name = "cost_map_ros/example.yaml";
00031   std::shared_ptr<cost_map::LoadImageBundle> loader;
00032   try {
00033     loader = std::make_shared<cost_map::LoadImageBundle>(image_resource_name);
00034     /****************************************
00035     ** Inflate & Deflate
00036     ****************************************/
00037     float inscribed_radius = 0.3;
00038     float inflation_radius = 0.8;
00039     float inflation_exponential_rate = 5.0;
00040     cost_map::Inflate inflate;
00041     cost_map::ROSInflationComputer inflation_computer(inscribed_radius, inflation_exponential_rate);
00042     inflate("obstacle_costs", "inflated_costs",
00043             inflation_radius,
00044             inflation_computer,
00045             *(loader->cost_map)
00046             );
00047     cost_map::Deflate deflate;
00048     deflate("inflated_costs", "deflated_costs", *(loader->cost_map));
00049   } catch (const std::exception& e) { // *spank* shouldn't do this...catch the type exactly!
00050     std::cout << ecl::red << "[ERROR] " << e.what() << ecl::reset << std::endl;
00051     return EXIT_FAILURE;
00052   }
00053   /****************************************
00054   ** Publish
00055   ****************************************/
00056   bool latched = true;
00057   ros::Publisher obstacle_publisher = nodehandle.advertise<nav_msgs::OccupancyGrid>("obstacle_layer", 1, latched);
00058   ros::Publisher inflation_publisher = nodehandle.advertise<nav_msgs::OccupancyGrid>("inflation_layer", 1, latched);
00059   ros::Publisher deflation_publisher = nodehandle.advertise<nav_msgs::OccupancyGrid>("deflation_layer", 1, latched);
00060 
00061   nav_msgs::OccupancyGrid obstacle_occupancy_grid_msg, inflated_occupancy_grid_msg, deflated_occupancy_grid_msg;
00062   cost_map::toOccupancyGrid(*(loader->cost_map), "obstacle_costs", obstacle_occupancy_grid_msg);
00063   cost_map::toOccupancyGrid(*(loader->cost_map), "inflated_costs", inflated_occupancy_grid_msg);
00064   cost_map::toOccupancyGrid(*(loader->cost_map), "deflated_costs", deflated_occupancy_grid_msg);
00065   obstacle_publisher.publish(obstacle_occupancy_grid_msg);
00066   inflation_publisher.publish(inflated_occupancy_grid_msg);
00067   deflation_publisher.publish(deflated_occupancy_grid_msg);
00068 
00069   /****************************************
00070   ** Spin
00071   ****************************************/
00072   ros::spin();
00073   return EXIT_SUCCESS;
00074 }
00075 


cost_map_demos
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 20:28:06