Skip to content

Commit 5423cec

Browse files
committed
remove ros from base python module
fix import of param file
1 parent 6280caf commit 5423cec

File tree

2 files changed

+3
-23
lines changed

2 files changed

+3
-23
lines changed

elevation_mapping_cupy/elevation_mapping_cupy/elevation_mapping.py

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,6 @@ def __init__(self, param: Parameter):
5757
Args:
5858
param (elevation_mapping_cupy.parameter.Parameter):
5959
"""
60-
# Initialize the ROS logger
61-
self.logger = rclpy.logging.get_logger('elevation_map')
6260

6361
self.param = param
6462
self.data_type = self.param.data_type
@@ -243,25 +241,6 @@ def compile_kernels(self):
243241
self.min_filtered_mask = cp.zeros((self.cell_n, self.cell_n), dtype=self.data_type)
244242
self.mask = cp.zeros((self.cell_n, self.cell_n), dtype=self.data_type)
245243

246-
# Log parameter values before kernel initialization
247-
self.logger.info("Initializing add_points_kernel with parameters:")
248-
self.logger.info(f" resolution: {self.resolution}")
249-
self.logger.info(f" cell_n: {self.cell_n}")
250-
self.logger.info(f" sensor_noise_factor: {self.param.sensor_noise_factor}")
251-
self.logger.info(f" mahalanobis_thresh: {self.param.mahalanobis_thresh}")
252-
self.logger.info(f" outlier_variance: {self.param.outlier_variance}")
253-
self.logger.info(f" wall_num_thresh: {self.param.wall_num_thresh}")
254-
self.logger.info(f" max_ray_length: {self.param.max_ray_length}")
255-
self.logger.info(f" cleanup_step: {self.param.cleanup_step}")
256-
self.logger.info(f" min_valid_distance: {self.param.min_valid_distance}")
257-
self.logger.info(f" max_height_range: {self.param.max_height_range}")
258-
self.logger.info(f" cleanup_cos_thresh: {self.param.cleanup_cos_thresh}")
259-
self.logger.info(f" ramped_height_range_a: {self.param.ramped_height_range_a}")
260-
self.logger.info(f" ramped_height_range_b: {self.param.ramped_height_range_b}")
261-
self.logger.info(f" ramped_height_range_c: {self.param.ramped_height_range_c}")
262-
self.logger.info(f" enable_edge_sharpen: {self.param.enable_edge_sharpen}")
263-
self.logger.info(f" enable_visibility_cleanup: {self.param.enable_visibility_cleanup}")
264-
265244
self.add_points_kernel = add_points_kernel(
266245
self.resolution,
267246
self.cell_n,

elevation_mapping_cupy/launch/elevation_mapping_turtle.launch.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
from ament_index_python.packages import get_package_share_directory
55
from launch.actions import DeclareLaunchArgument
66
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
7+
from launch_ros.descriptions import ParameterFile
78

89

910
def generate_launch_description():
@@ -47,11 +48,11 @@ def generate_launch_description():
4748
)
4849
elevation_mapping_node = Node(
4950
package='elevation_mapping_cupy',
50-
executable='elevation_mapping_node.py',
51+
executable='elevation_mapping_node',
5152
name='elevation_mapping_node',
5253
output='screen',
5354
parameters=[
54-
core_param_path,
55+
ParameterFile(core_param_path, allow_substs=True),
5556
turtle_param_path,
5657
{'use_sim_time': use_sim_time}
5758
]

0 commit comments

Comments
 (0)