Skip to content

Commit 7e1ff0a

Browse files
SteveMacenskienricosutera
authored andcommitted
changing costmap layers private to protected (ros-navigation#3722)
Signed-off-by: enricosutera <enricosutera@outlook.com>
1 parent a8eac63 commit 7e1ff0a

File tree

4 files changed

+2
-4
lines changed

4 files changed

+2
-4
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -188,7 +188,6 @@ class InflationLayer : public Layer
188188
*/
189189
void onFootprintChanged() override;
190190

191-
private:
192191
/**
193192
* @brief Lookup pre-computed distances
194193
* @param mx The x coordinate of the current cell

nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,7 @@ class RangeSensorLayer : public CostmapLayer
128128
*/
129129
void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message);
130130

131-
private:
131+
protected:
132132
/**
133133
* @brief Processes all sensors into the costmap buffered from callbacks
134134
*/

nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ class StaticLayer : public CostmapLayer
123123
*/
124124
virtual void matchSize();
125125

126-
private:
126+
protected:
127127
/**
128128
* @brief Get parameters of layer
129129
*/

nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,6 @@ class VoxelLayer : public ObstacleLayer
133133
*/
134134
virtual void resetMaps();
135135

136-
private:
137136
/**
138137
* @brief Use raycasting between 2 points to clear freespace
139138
*/

0 commit comments

Comments
 (0)