Skip to content

Commit 13f518a

Browse files
authored
Adding parameter for minimum range for raycasting to clear obstacles (#2126)
* Adding minimum range parameter for raytrace clearing * Comments in tests * Uncrustify checks * Modified default value of raytrace_min_range param and moved computation below plugin layer * Tests for voxel layer raytracing * Uncrustify checks * Addressed pull request #2126 comments * Using min range parameter for marking also * Correcting build warnings * Correct build fails * Merging changes * Adding comments * Added unit tests for obstacle layer and addressed PR comments * Addressed flake errors * Flake8 errors * Correcting W291 Flake8 error * Variable name and comments changes * Added raytracing params to the params files * Modifying parameter names for obstacle marking
1 parent 567f8c8 commit 13f518a

File tree

27 files changed

+284
-108
lines changed

27 files changed

+284
-108
lines changed

doc/parameters/param_list.md

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -119,8 +119,10 @@ When `plugins` parameter is not overridden, the following default plugins are lo
119119
| `<data source>`.inf_is_valid | false | Are infinite returns from laser scanners valid measurements |
120120
| `<data source>`.marking | true | Whether source should mark in costmap |
121121
| `<data source>`.clearing | false | Whether source should raytrace clear in costmap |
122-
| `<data source>`.obstacle_range | 2.5 | Maximum range to mark obstacles in costmap |
123-
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
122+
| `<data source>`.obstacle_max_range | 2.5 | Maximum range to mark obstacles in costmap |
123+
| `<data_source>`.obstacle_min_range | 0.0 | Minimum range to mark obstacles in costmap |
124+
| `<data source>`.raytrace_max_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
125+
| `<data_source>`.raytrace_min_range | 0.0 | Minimum range to raytrace clear obstacles from costmap |
124126

125127
## range_sensor_layer plugin
126128

@@ -168,8 +170,10 @@ When `plugins` parameter is not overridden, the following default plugins are lo
168170
| `<data source>`.inf_is_valid | false | Are infinite returns from laser scanners valid measurements |
169171
| `<data source>`.marking | true | Whether source should mark in costmap |
170172
| `<data source>`.clearing | false | Whether source should raytrace clear in costmap |
171-
| `<data source>`.obstacle_range | 2.5 | Maximum range to mark obstacles in costmap |
172-
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
173+
| `<data source>`.obstacle_max_range | 2.5 | Maximum range to mark obstacles in costmap |
174+
| `<data_source>`.obstacle_min_range | 0.0 | Minimum range to mark obstacles in costmap |
175+
| `<data source>`.raytrace_max_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
176+
| `<data_source>`.raytrace_min_range | 0.0 | Minimum range to raytrace clear obstacles from costmap |
173177

174178
## keepout filter
175179

nav2_bringup/bringup/launch/tb3_simulation_launch.py

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,8 @@ def generate_launch_description():
7676

7777
declare_map_yaml_cmd = DeclareLaunchArgument(
7878
'map',
79-
default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
79+
default_value=os.path.join(
80+
bringup_dir, 'maps', 'turtlebot3_world.yaml'),
8081
description='Full path to map file to load')
8182

8283
declare_use_sim_time_cmd = DeclareLaunchArgument(
@@ -102,7 +103,8 @@ def generate_launch_description():
102103

103104
declare_rviz_config_file_cmd = DeclareLaunchArgument(
104105
'rviz_config_file',
105-
default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
106+
default_value=os.path.join(
107+
bringup_dir, 'rviz', 'nav2_default_view.rviz'),
106108
description='Full path to the RVIZ config file to use')
107109

108110
declare_use_simulator_cmd = DeclareLaunchArgument(
@@ -130,7 +132,7 @@ def generate_launch_description():
130132
# TODO(orduno) Switch back once ROS argument passing has been fixed upstream
131133
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/91
132134
# default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'),
133-
# 'worlds/turtlebot3_worlds/waffle.model'),
135+
# worlds/turtlebot3_worlds/waffle.model')
134136
default_value=os.path.join(bringup_dir, 'worlds', 'waffle.model'),
135137
description='Full path to world model file to load')
136138

@@ -141,7 +143,8 @@ def generate_launch_description():
141143
cwd=[launch_dir], output='screen')
142144

143145
start_gazebo_client_cmd = ExecuteProcess(
144-
condition=IfCondition(PythonExpression([use_simulator, ' and not ', headless])),
146+
condition=IfCondition(PythonExpression(
147+
[use_simulator, ' and not ', headless])),
145148
cmd=['gzclient'],
146149
cwd=[launch_dir], output='screen')
147150

@@ -159,14 +162,16 @@ def generate_launch_description():
159162
arguments=[urdf])
160163

161164
rviz_cmd = IncludeLaunchDescription(
162-
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
165+
PythonLaunchDescriptionSource(
166+
os.path.join(launch_dir, 'rviz_launch.py')),
163167
condition=IfCondition(use_rviz),
164168
launch_arguments={'namespace': '',
165169
'use_namespace': 'False',
166170
'rviz_config': rviz_config_file}.items())
167171

168172
bringup_cmd = IncludeLaunchDescription(
169-
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
173+
PythonLaunchDescriptionSource(
174+
os.path.join(launch_dir, 'bringup_launch.py')),
170175
launch_arguments={'namespace': namespace,
171176
'use_namespace': use_namespace,
172177
'slam': slam,

nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,10 @@ local_costmap:
170170
max_obstacle_height: 2.0
171171
clearing: True
172172
marking: True
173+
raytrace_max_range: 3.0
174+
raytrace_min_range: 0.0
175+
obstacle_max_range: 2.5
176+
obstacle_min_range: 0.0
173177
static_layer:
174178
map_subscribe_transient_local: True
175179
always_send_full_costmap: True
@@ -193,6 +197,10 @@ global_costmap:
193197
max_obstacle_height: 2.0
194198
clearing: True
195199
marking: True
200+
raytrace_max_range: 3.0
201+
raytrace_min_range: 0.0
202+
obstacle_max_range: 2.5
203+
obstacle_min_range: 0.0
196204
static_layer:
197205
map_subscribe_transient_local: True
198206
always_send_full_costmap: True

nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,10 @@ local_costmap:
170170
max_obstacle_height: 2.0
171171
clearing: True
172172
marking: True
173+
raytrace_max_range: 3.0
174+
raytrace_min_range: 0.0
175+
obstacle_max_range: 2.5
176+
obstacle_min_range: 0.0
173177
static_layer:
174178
map_subscribe_transient_local: True
175179
always_send_full_costmap: True
@@ -193,6 +197,10 @@ global_costmap:
193197
max_obstacle_height: 2.0
194198
clearing: True
195199
marking: True
200+
raytrace_max_range: 3.0
201+
raytrace_min_range: 0.0
202+
obstacle_max_range: 2.5
203+
obstacle_min_range: 0.0
196204
static_layer:
197205
map_subscribe_transient_local: True
198206
always_send_full_costmap: True

nav2_bringup/bringup/params/nav2_params.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -188,6 +188,10 @@ local_costmap:
188188
clearing: True
189189
marking: True
190190
data_type: "LaserScan"
191+
raytrace_max_range: 3.0
192+
raytrace_min_range: 0.0
193+
obstacle_max_range: 2.5
194+
obstacle_min_range: 0.0
191195
static_layer:
192196
map_subscribe_transient_local: True
193197
always_send_full_costmap: True
@@ -220,6 +224,10 @@ global_costmap:
220224
clearing: True
221225
marking: True
222226
data_type: "LaserScan"
227+
raytrace_max_range: 3.0
228+
raytrace_min_range: 0.0
229+
obstacle_max_range: 2.5
230+
obstacle_min_range: 0.0
223231
static_layer:
224232
plugin: "nav2_costmap_2d::StaticLayer"
225233
map_subscribe_transient_local: True

nav2_common/nav2_common/launch/replace_string.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ def perform(self, context: launch.LaunchContext) -> Text:
5151
try:
5252
input_file = open(launch.utilities.perform_substitutions(context, self.name), 'r')
5353
self.replace(input_file, output_file, replacements)
54-
except Exception as err:
54+
except Exception as err: # noqa: B902
5555
print('ReplaceString substitution error: ', err)
5656
finally:
5757
input_file.close()

nav2_costmap_2d/cfg/ObstaclePlugin.cfg

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@ combo_enum = gen.enum([gen.const("Overwrite", int_t, 0, "Overwrite values"),
1515
gen.add("combination_method", int_t, 0, "Method for combining two layers", 1, edit_method=combo_enum)
1616

1717

18-
#gen.add("max_obstacle_range", double_t, 0, "The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters.", 2.5, 0, 50)
19-
#gen.add("raytrace_range", double_t, 0, "The default range in meters at which to raytrace out obstacles from the map using sensor data.", 3, 0, 50)
18+
# gen.add("obstacle_max_range", double_t, 0, "The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters.", 2.5, 0, 50)
19+
# gen.add("obstacle_min_range", double_t, 0, "The default minimum distance from the robot at which an obstacle will be inserted into the cost map in meters.", 0.0, 0, 50)
20+
# gen.add("raytrace_max_range", double_t, 0, "The default maximum range in meters at which to raytrace out obstacles from the map using sensor data.", 3, 0, 50)
21+
# gen.add("raytrace_min_range", double_t, 0, "The default minimum range in meters from which to raytrace out obstacles from the map using sensor data.", 0.0, 0, 50)
2022
exit(gen.generate("nav2_costmap_2d", "nav2_costmap_2d", "ObstaclePlugin"))

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp

Lines changed: 21 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -391,12 +391,13 @@ class Costmap2D
391391
* @param x1 The ending x coordinate
392392
* @param y1 The ending y coordinate
393393
* @param max_length The maximum desired length of the segment... allows you to not go all the way to the endpoint
394+
* @param min_length The minimum desired length of the segment
394395
*/
395396
template<class ActionType>
396397
inline void raytraceLine(
397398
ActionType at, unsigned int x0, unsigned int y0, unsigned int x1,
398399
unsigned int y1,
399-
unsigned int max_length = UINT_MAX)
400+
unsigned int max_length = UINT_MAX, unsigned int min_length = 0)
400401
{
401402
int dx = x1 - x0;
402403
int dy = y1 - y0;
@@ -407,27 +408,39 @@ class Costmap2D
407408
int offset_dx = sign(dx);
408409
int offset_dy = sign(dy) * size_x_;
409410

410-
unsigned int offset = y0 * size_x_ + x0;
411-
412411
// we need to chose how much to scale our dominant dimension,
413412
// based on the maximum length of the line
414413
double dist = std::hypot(dx, dy);
415-
double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
414+
if (dist < min_length) {
415+
return;
416+
}
417+
418+
// Adjust starting point and offset to start from min_length distance
419+
unsigned int min_x0 = (unsigned int)(x0 + dx / dist * min_length);
420+
unsigned int min_y0 = (unsigned int)(y0 + dy / dist * min_length);
421+
unsigned int offset = min_y0 * size_x_ + min_x0;
416422

423+
double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
424+
unsigned int length;
417425
// if x is dominant
418426
if (abs_dx >= abs_dy) {
419427
int error_y = abs_dx / 2;
428+
429+
// Subtract min_length from total length since initial point (x0, y0) has been adjusted by min Z
430+
length = (unsigned int)(scale * abs_dx) - min_length;
431+
420432
bresenham2D(
421-
at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset,
422-
(unsigned int)(scale * abs_dx));
433+
at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, length);
423434
return;
424435
}
425436

426437
// otherwise y is dominant
427438
int error_x = abs_dy / 2;
439+
440+
// Subtract min_length from total length since initial point (x0, y0) has been adjusted by min Z
441+
length = (unsigned int)(scale * abs_dy) - min_length;
428442
bresenham2D(
429-
at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset,
430-
(unsigned int)(scale * abs_dy));
443+
at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, length);
431444
}
432445

433446
private:

nav2_costmap_2d/include/nav2_costmap_2d/observation.hpp

Lines changed: 24 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,9 @@ class Observation
5050
* @brief Creates an empty observation
5151
*/
5252
Observation()
53-
: cloud_(new sensor_msgs::msg::PointCloud2()), obstacle_range_(0.0), raytrace_range_(0.0)
53+
: cloud_(new sensor_msgs::msg::PointCloud2()), obstacle_max_range_(0.0), obstacle_min_range_(0.0),
54+
raytrace_max_range_(0.0),
55+
raytrace_min_range_(0.0)
5456
{
5557
}
5658

@@ -68,14 +70,19 @@ class Observation
6870
* @brief Creates an observation from an origin point and a point cloud
6971
* @param origin The origin point of the observation
7072
* @param cloud The point cloud of the observation
71-
* @param obstacle_range The range out to which an observation should be able to insert obstacles
72-
* @param raytrace_range The range out to which an observation should be able to clear via raytracing
73+
* @param obstacle_max_range The range out to which an observation should be able to insert obstacles
74+
* @param obstacle_min_range The range from which an observation should be able to insert obstacles
75+
* @param raytrace_max_range The range out to which an observation should be able to clear via raytracing
76+
* @param raytrace_min_range The range from which an observation should be able to clear via raytracing
7377
*/
7478
Observation(
7579
geometry_msgs::msg::Point & origin, const sensor_msgs::msg::PointCloud2 & cloud,
76-
double obstacle_range, double raytrace_range)
80+
double obstacle_max_range, double obstacle_min_range, double raytrace_max_range,
81+
double raytrace_min_range)
7782
: origin_(origin), cloud_(new sensor_msgs::msg::PointCloud2(cloud)),
78-
obstacle_range_(obstacle_range), raytrace_range_(raytrace_range)
83+
obstacle_max_range_(obstacle_max_range), obstacle_min_range_(obstacle_min_range),
84+
raytrace_max_range_(raytrace_max_range), raytrace_min_range_(
85+
raytrace_min_range)
7986
{
8087
}
8188

@@ -85,24 +92,30 @@ class Observation
8592
*/
8693
Observation(const Observation & obs)
8794
: origin_(obs.origin_), cloud_(new sensor_msgs::msg::PointCloud2(*(obs.cloud_))),
88-
obstacle_range_(obs.obstacle_range_), raytrace_range_(obs.raytrace_range_)
95+
obstacle_max_range_(obs.obstacle_max_range_), obstacle_min_range_(obs.obstacle_min_range_),
96+
raytrace_max_range_(obs.raytrace_max_range_),
97+
raytrace_min_range_(obs.raytrace_min_range_)
8998
{
9099
}
91100

92101
/**
93102
* @brief Creates an observation from a point cloud
94103
* @param cloud The point cloud of the observation
95-
* @param obstacle_range The range out to which an observation should be able to insert obstacles
104+
* @param obstacle_max_range The range out to which an observation should be able to insert obstacles
105+
* @param obstacle_min_range The range from which an observation should be able to insert obstacles
96106
*/
97-
Observation(const sensor_msgs::msg::PointCloud2 & cloud, double obstacle_range)
98-
: cloud_(new sensor_msgs::msg::PointCloud2(cloud)), obstacle_range_(obstacle_range),
99-
raytrace_range_(0.0)
107+
Observation(
108+
const sensor_msgs::msg::PointCloud2 & cloud, double obstacle_max_range,
109+
double obstacle_min_range)
110+
: cloud_(new sensor_msgs::msg::PointCloud2(cloud)), obstacle_max_range_(obstacle_max_range),
111+
obstacle_min_range_(obstacle_min_range),
112+
raytrace_max_range_(0.0), raytrace_min_range_(0.0)
100113
{
101114
}
102115

103116
geometry_msgs::msg::Point origin_;
104117
sensor_msgs::msg::PointCloud2 * cloud_;
105-
double obstacle_range_, raytrace_range_;
118+
double obstacle_max_range_, obstacle_min_range_, raytrace_max_range_, raytrace_min_range_;
106119
};
107120

108121
} // namespace nav2_costmap_2d

nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,10 @@ class ObservationBuffer
6666
* @param expected_update_rate How often this buffer is expected to be updated, 0 means there is no limit
6767
* @param min_obstacle_height The minimum height of a hitpoint to be considered legal
6868
* @param max_obstacle_height The minimum height of a hitpoint to be considered legal
69-
* @param obstacle_range The range to which the sensor should be trusted for inserting obstacles
70-
* @param raytrace_range The range to which the sensor should be trusted for raytracing to clear out space
69+
* @param obstacle_max_range The range to which the sensor should be trusted for inserting obstacles
70+
* @param obstacle_min_range The range from which the sensor should be trusted for inserting obstacles
71+
* @param raytrace_max_range The range to which the sensor should be trusted for raytracing to clear out space
72+
* @param raytrace_min_range The range from which the sensor should be trusted for raytracing to clear out space
7173
* @param tf2_buffer A reference to a tf2 Buffer
7274
* @param global_frame The frame to transform PointClouds into
7375
* @param sensor_frame The frame of the origin of the sensor, can be left blank to be read from the messages
@@ -78,8 +80,10 @@ class ObservationBuffer
7880
std::string topic_name,
7981
double observation_keep_time,
8082
double expected_update_rate,
81-
double min_obstacle_height, double max_obstacle_height, double obstacle_range,
82-
double raytrace_range, tf2_ros::Buffer & tf2_buffer, std::string global_frame,
83+
double min_obstacle_height, double max_obstacle_height, double obstacle_max_range,
84+
double obstacle_min_range,
85+
double raytrace_max_range, double raytrace_min_range, tf2_ros::Buffer & tf2_buffer,
86+
std::string global_frame,
8387
std::string sensor_frame,
8488
tf2::Duration tf_tolerance);
8589

@@ -146,7 +150,7 @@ class ObservationBuffer
146150
std::string topic_name_;
147151
double min_obstacle_height_, max_obstacle_height_;
148152
std::recursive_mutex lock_; ///< @brief A lock for accessing data in callbacks safely
149-
double obstacle_range_, raytrace_range_;
153+
double obstacle_max_range_, obstacle_min_range_, raytrace_max_range_, raytrace_min_range_;
150154
tf2::Duration tf_tolerance_;
151155
};
152156
} // namespace nav2_costmap_2d

0 commit comments

Comments
 (0)