|
20 | 20 | # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, |
21 | 21 | # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE |
22 | 22 | # SOFTWARE. |
| 23 | +import os |
| 24 | + |
23 | 25 | import numpy as np |
24 | 26 | import rclpy |
| 27 | +from ament_index_python.packages import get_package_share_directory |
25 | 28 | from kiss_slam_ros.conversions import ( |
26 | 29 | build_map, |
27 | 30 | build_odometry, |
@@ -52,7 +55,13 @@ def __init__(self): |
52 | 55 | """Create parameters, subscriptions, publishers, and set up SLAM""" |
53 | 56 | super().__init__("kiss_slam_node") |
54 | 57 |
|
55 | | - # TODO an argument to set the SLAM config, with a sensible default value |
| 58 | + points_topic_desc = ParameterDescriptor( |
| 59 | + description="Path to yaml file to use as KISS-SLAM config." |
| 60 | + ) |
| 61 | + share_dir = get_package_share_directory("kiss_slam_ros") |
| 62 | + default_slam_config = os.path.join(share_dir, "config", "default.yaml") |
| 63 | + self.declare_parameter("slam_config", default_slam_config, points_topic_desc) |
| 64 | + self.slam_config = self.get_parameter("slam_config").value |
56 | 65 |
|
57 | 66 | points_topic_desc = ParameterDescriptor( |
58 | 67 | description="What topic to listen on for PointCloud2 messages." |
@@ -88,7 +97,7 @@ def __init__(self): |
88 | 97 | self.map_publisher = self.create_publisher(OccupancyGrid, "map", 10) |
89 | 98 | self.tf_broadcaster = TransformBroadcaster(self) |
90 | 99 |
|
91 | | - self.slam_config = load_config(None) |
| 100 | + self.slam_config = load_config(self.slam_config) |
92 | 101 | self.slam = KissSLAM(self.slam_config) |
93 | 102 | self.mapper = OccupancyGridMapper(self.slam_config.occupancy_mapper) |
94 | 103 | self.ref_ground_alignment = None |
|
0 commit comments