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


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10