output.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
32 
33 #include <geometry_msgs/PolygonStamped.h>
34 #include <nav_msgs/OccupancyGrid.h>
35 #include <costmap_cspace_msgs/CSpace3D.h>
36 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
37 
39 
40 namespace costmap_cspace
41 {
43 {
44 public:
45  using Ptr = std::shared_ptr<Costmap3dLayerOutput>;
46  using Callback = boost::function<bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)>;
47 
48 protected:
51 
52 public:
54  {
55  }
57  {
58  cb_ = cb;
59  }
60  void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info)
61  {
62  }
63 
64 protected:
65  int getRangeMax() const
66  {
67  return 0;
68  }
69  bool updateChain(const bool output)
70  {
71  auto update_msg = generateUpdateMsg();
72  if (cb_ && output)
73  return cb_(map_, update_msg);
74  return true;
75  }
77  const nav_msgs::OccupancyGrid::ConstPtr& map,
78  const UpdatedRegion& region)
79  {
80  }
81  costmap_cspace_msgs::CSpace3DUpdate::Ptr generateUpdateMsg()
82  {
83  costmap_cspace_msgs::CSpace3DUpdate::Ptr update_msg(new costmap_cspace_msgs::CSpace3DUpdate);
84  update_msg->header = map_->header;
85  map_->header.stamp = region_.stamp_;
86  int update_x = region_.x_;
87  int update_y = region_.y_;
88  int update_width = region_.width_;
89  int update_height = region_.height_;
90  if (update_x < 0)
91  {
92  update_width += update_x;
93  update_x = 0;
94  }
95  if (update_y < 0)
96  {
97  update_height += update_y;
98  update_y = 0;
99  }
100  if (update_x + update_width > static_cast<int>(map_->info.width))
101  {
102  update_width = map_->info.width - update_x;
103  }
104  if (update_y + update_height > static_cast<int>(map_->info.height))
105  {
106  update_height = map_->info.height - update_y;
107  }
108  UpdatedRegion region(
109  update_x,
110  update_y,
111  region_.yaw_,
112  update_width,
113  update_height,
114  region_.angle_);
115  UpdatedRegion region_merged = region;
116  region_merged.merge(region_prev_);
117  region_prev_ = region;
119 
120  update_msg->x = region_merged.x_;
121  update_msg->y = region_merged.y_;
122  update_msg->width = region_merged.width_;
123  update_msg->height = region_merged.height_;
124  update_msg->yaw = region_merged.yaw_;
125  update_msg->angle = region_merged.angle_;
126  update_msg->data.resize(update_msg->width * update_msg->height * update_msg->angle);
127 
128  for (int i = 0; i < static_cast<int>(update_msg->width); i++)
129  {
130  for (int j = 0; j < static_cast<int>(update_msg->height); j++)
131  {
132  for (int k = 0; k < static_cast<int>(update_msg->angle); k++)
133  {
134  const int x2 = update_msg->x + i;
135  const int y2 = update_msg->y + j;
136  const int yaw2 = update_msg->yaw + k;
137 
138  const auto& m = map_->getCost(x2, y2, yaw2);
139  const size_t addr = (k * update_msg->height + j) * update_msg->width + i;
140  ROS_ASSERT(addr < update_msg->data.size());
141  auto& up = update_msg->data[addr];
142  up = m;
143  }
144  }
145  }
146  return update_msg;
147  }
148 };
149 } // namespace costmap_cspace
150 
151 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
boost::function< bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)> Callback
Definition: output.h:46
void merge(const UpdatedRegion &region)
Definition: base.h:116
costmap_cspace_msgs::CSpace3DUpdate::Ptr generateUpdateMsg()
Definition: output.h:81
void loadConfig(XmlRpc::XmlRpcValue config)
Definition: output.h:53
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition: output.h:60
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:210
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion &region)
Definition: output.h:76
#define ROS_ASSERT(cond)
void setHandler(Callback cb)
Definition: output.h:56
bool updateChain(const bool output)
Definition: output.h:69


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:48