Skip to content

Commit 22ef92d

Browse files
committed
requested changes
1 parent 7583c6b commit 22ef92d

File tree

3 files changed

+10
-8
lines changed

3 files changed

+10
-8
lines changed

README.md

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ Required dependencies ROS Kinetic, navigation, OpenVDB, TBB.
101101

102102
An example fully-described configuration is shown below.
103103

104-
Note: We supply two PCL filters within STVL to massage the data to lower compute overhead. STVL has an approximate voxel filter to make the data more sparse if very dense. It also has a passthrough filter to limit processing data within the valid minimum to maximum height bounds. The voxel filter is recommended if it lowers CPU overhead, otherwise, passthrough filter. No filter is also available if you pre-process your data or are not interested in performance optimizations.
104+
Note: We supply two PCL filters within STVL to massage the data to lower compute overhead. STVL has an approximate voxel filter to make the data more sparse if very dense. It also has a passthrough filter to limit processing data within the valid minimum to maximum height bounds. The voxel filter is recommended if it lowers CPU overhead, otherwise, passthrough filter. No filter is also available if you pre-process your data or are not interested in performance optimizations. Filters have "relative" variants made to use robot's frame for obstacle classification instead of the global frame in case of navigating sloped surfaces.
105105

106106
```
107107
rgbd_obstacle_layer:
@@ -113,7 +113,9 @@ rgbd_obstacle_layer:
113113
observation_persistence: 0.0 #seconds
114114
max_obstacle_height: 2.0 #meters
115115
mark_threshold: 0 #voxel height
116-
update_footprint_enabled: true
116+
update_footprint_enabled: true
117+
footprint_projection_enabled: true #default off, recommended when using 3d IMU data. Uses tf2 to transform the footprint
118+
robot_base_frame: "base_link" #frame to use with footprint_projection_enabled
117119
combination_method: 1 #1=max, 0=override
118120
obstacle_range: 3.0 #meters
119121
origin_z: 0.0 #meters
@@ -133,7 +135,8 @@ rgbd_obstacle_layer:
133135
observation_persistence: 0.0 #default 0, use all measurements taken during now-value, 0=latest
134136
inf_is_valid: false #default false, for laser scans
135137
clear_after_reading: true #default false, clear the buffer after the layer gets readings from it
136-
filter: "voxel" #default passthrough, apply "voxel", "passthrough", or no filter to sensor data, recommended to have at one filter on
138+
filter: "voxel" #default passthrough, apply "voxel", "passthrough", "voxel_relative", "passthrough_relative", or no filter to sensor data, recommended to have at one filter on
139+
z_reference_frame: "base_link" #default global_frame, use with *_relative filters as a frame for obstacle classification based on z coordinate
137140
voxel_min_points: 0 #default 0, minimum points per voxel for voxel filter
138141
rgbd1_clear:
139142
enabled: true #default true, can be toggled on/off with associated service call

spatio_temporal_voxel_layer/example/uneven_terrain_config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ global_costmap:
1111
mark_threshold: 0 # voxel height
1212
update_footprint_enabled: true
1313
footprint_projection_enabled: true # default off, strongly recommended when using 3d IMU data
14-
footprint_frame: "base_link" # necessary for use with footprint projection,
14+
robot_base_frame: "base_link" # necessary for use with footprint projection,
1515
combination_method: 1 # 1=max, 0=override
1616
origin_z: 0.0 # meters
1717
publish_voxel_map: false # default off

spatio_temporal_voxel_layer/src/spatio_temporal_voxel_layer.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -570,11 +570,10 @@ bool SpatioTemporalVoxelLayer::updateFootprint(
570570
tf_->lookupTransform(
571571
_global_frame, _robot_base_frame,
572572
rclcpp::Clock.now());
573-
std::vector<geometry_msgs::Point> temp_footprint = getFootprint();
574-
for (unsigned int i = 0; i < temp_footprint.size(); i++) {
575-
tf2::doTransform(temp_footprint[i], temp_footprint[i], tf_footprint_stamped);
573+
for (unsigned int i = 0; i < _transformed_footprint.size(); i++) {
574+
tf2::doTransform(_transformed_footprint[i], _transformed_footprint[i], tf_footprint_stamped);
576575
touch(
577-
temp_footprint[i].x, temp_footprint[i].y,
576+
_transformed_footprint[i].x, _transformed_footprint[i].y,
578577
min_x, min_y, max_x, max_y);
579578
}
580579
} catch (tf2::TransformException &ex) {

0 commit comments

Comments
 (0)