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 <memory>
34 
35 #include <costmap_cspace_msgs/CSpace3D.h>
36 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
37 #include <geometry_msgs/PolygonStamped.h>
38 #include <nav_msgs/OccupancyGrid.h>
39 
41 
42 namespace costmap_cspace
43 {
44 template <class CALLBACK>
46 {
47 public:
48  using Ptr = std::shared_ptr<Costmap3dLayerOutput>;
49 
50 protected:
51  CALLBACK cb_;
53 
54 public:
56  {
57  }
58  void setHandler(CALLBACK cb)
59  {
60  cb_ = cb;
61  }
62  void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info)
63  {
64  }
65 
66 protected:
67  int getRangeMax() const
68  {
69  return 0;
70  }
72  const nav_msgs::OccupancyGrid::ConstPtr& map,
73  const UpdatedRegion& region)
74  {
75  }
76 };
77 
79  : public Costmap3dLayerOutput<boost::function<bool(const typename costmap_cspace::CSpace3DMsg::Ptr&)>>
80 {
81 public:
82  using Ptr = std::shared_ptr<Costmap3dStaticLayerOutput>;
83 
84 protected:
85  bool updateChain(const bool output)
86  {
87  if (cb_ && output)
88  return cb_(map_);
89  return true;
90  }
91 };
92 
94  : public Costmap3dLayerOutput<boost::function<bool(const typename costmap_cspace::CSpace3DMsg::Ptr&,
95  const typename costmap_cspace_msgs::CSpace3DUpdate::Ptr&)>>
96 {
97 public:
98  using Ptr = std::shared_ptr<Costmap3dUpdateLayerOutput>;
99 
100 protected:
101  bool updateChain(const bool output)
102  {
103  auto update_msg = generateUpdateMsg();
104  if (cb_ && output)
105  return cb_(map_, update_msg);
106  return true;
107  }
108 
109  costmap_cspace_msgs::CSpace3DUpdate::Ptr generateUpdateMsg()
110  {
111  costmap_cspace_msgs::CSpace3DUpdate::Ptr update_msg(new costmap_cspace_msgs::CSpace3DUpdate);
112  update_msg->header = map_->header;
113  map_->header.stamp = region_.stamp_;
114 
115  UpdatedRegion region = region_;
116  region.normalize(map_->info.width, map_->info.height);
117 
118  UpdatedRegion region_merged = region;
119  region_merged.merge(region_prev_);
120  region_prev_ = region;
122 
123  if (region.width_ == 0 || region.height_ == 0)
124  {
125  return nullptr;
126  }
127 
128  update_msg->x = region_merged.x_;
129  update_msg->y = region_merged.y_;
130  update_msg->width = region_merged.width_;
131  update_msg->height = region_merged.height_;
132  update_msg->yaw = region_merged.yaw_;
133  update_msg->angle = region_merged.angle_;
134  update_msg->data.resize(update_msg->width * update_msg->height * update_msg->angle);
135  if ((update_msg->x == 0) && (update_msg->y == 0) && (update_msg->yaw == 0) &&
136  (update_msg->width == map_->info.width) && (update_msg->height == map_->info.height) &&
137  (update_msg->angle == map_->info.angle))
138  {
139  CSpace3DMsg::copyCells(*update_msg, 0, 0, 0, *map_, 0, 0, 0, update_msg->data.size());
140  return update_msg;
141  }
142  for (unsigned int k = 0; k < update_msg->angle; ++k)
143  {
144  for (unsigned int j = 0; j < update_msg->height; ++j)
145  {
146  CSpace3DMsg::copyCells(*update_msg, 0, j, k,
147  *map_, update_msg->x, update_msg->y + j, update_msg->yaw + k, update_msg->width);
148  }
149  }
150  return update_msg;
151  }
152 };
153 } // namespace costmap_cspace
154 
155 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
void normalize(const int full_width, const int full_height)
Definition: base.h:178
bool updateChain(const bool output)
Definition: output.h:85
void merge(const UpdatedRegion &region)
Definition: base.h:132
void setHandler(CALLBACK cb)
Definition: output.h:58
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion &region)
Definition: output.h:71
static void copyCells(CSpace3DMsg &to, const int &to_x, const int &to_y, const int &to_yaw, const CSpace3DMsg &from, const int &from_x, const int &from_y, const int &from_yaw, const int &copy_cell_num)
Definition: base.h:80
bool updateChain(const bool output)
Definition: output.h:101
costmap_cspace_msgs::CSpace3DUpdate::Ptr generateUpdateMsg()
Definition: output.h:109
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:255
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition: output.h:62
void loadConfig(XmlRpc::XmlRpcValue config)
Definition: output.h:55


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:38:47