inflations.cpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Includes
6 *****************************************************************************/
7 
9 #include <ecl/console.hpp>
10 #include <exception>
11 #include <memory>
12 #include <nav_msgs/OccupancyGrid.h>
13 #include <ros/ros.h>
14 #include <cstdlib>
15 
16 /*****************************************************************************
17 ** Main
18 *****************************************************************************/
19 
20 int main(int argc, char **argv) {
21  /****************************************
22  ** Ros
23  ****************************************/
24  ros::init(argc, argv, "inflations");
25  ros::NodeHandle nodehandle("~");
26 
27  /****************************************
28  ** Load
29  ****************************************/
30  std::string image_resource_name = "cost_map_ros/example.yaml";
31  std::shared_ptr<cost_map::LoadImageBundle> loader;
32  try {
33  loader = std::make_shared<cost_map::LoadImageBundle>(image_resource_name);
34  /****************************************
35  ** Inflate & Deflate
36  ****************************************/
37  float inscribed_radius = 0.3;
38  float inflation_radius = 0.8;
39  float inflation_exponential_rate = 5.0;
40  cost_map::Inflate inflate;
41  cost_map::ROSInflationComputer inflation_computer(inscribed_radius, inflation_exponential_rate);
42  inflate("obstacle_costs", "inflated_costs",
43  inflation_radius,
44  inflation_computer,
45  *(loader->cost_map)
46  );
47  cost_map::Deflate deflate;
48  deflate("inflated_costs", "deflated_costs", *(loader->cost_map));
49  } catch (const std::exception& e) { // *spank* shouldn't do this...catch the type exactly!
50  std::cout << ecl::red << "[ERROR] " << e.what() << ecl::reset << std::endl;
51  return EXIT_FAILURE;
52  }
53  /****************************************
54  ** Publish
55  ****************************************/
56  bool latched = true;
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);
60 
61  nav_msgs::OccupancyGrid obstacle_occupancy_grid_msg, inflated_occupancy_grid_msg, deflated_occupancy_grid_msg;
62  cost_map::toOccupancyGrid(*(loader->cost_map), "obstacle_costs", obstacle_occupancy_grid_msg);
63  cost_map::toOccupancyGrid(*(loader->cost_map), "inflated_costs", inflated_occupancy_grid_msg);
64  cost_map::toOccupancyGrid(*(loader->cost_map), "deflated_costs", 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);
68 
69  /****************************************
70  ** Spin
71  ****************************************/
72  ros::spin();
73  return EXIT_SUCCESS;
74 }
75 
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)
ROSCPP_DECL void spin()
void toOccupancyGrid(const cost_map::CostMap &cost_map, const std::string &layer, nav_msgs::OccupancyGrid &msg)
int main(int argc, char **argv)
Definition: inflations.cpp:20


cost_map_demos
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:04:00