diff --git a/clearpath_launch_generator/clearpath_launch_generator/sensors.py b/clearpath_launch_generator/clearpath_launch_generator/sensors.py index 77078cd..afe6b14 100644 --- a/clearpath_launch_generator/clearpath_launch_generator/sensors.py +++ b/clearpath_launch_generator/clearpath_launch_generator/sensors.py @@ -49,7 +49,6 @@ class BaseLaunch(): TOPIC_NAMESPACE = 'platform/sensors/' # Launch arguments - NAME = 'name' PARAMETERS = 'parameters' NAMESPACE = 'namespace' @@ -72,7 +71,6 @@ def __init__(self, sensor: BaseSensor, output_path: str = '/etc/clearpath/sensor self.sensor_parameters = sensor.get_ros_parameters() self.launch_args = { - self.NAME: self.get_name(), self.PARAMETERS: self.sensor_parameters_file, self.NAMESPACE: self.get_namespace() } @@ -92,13 +90,15 @@ def copy_parameters(default_params: dict, params: dict) -> dict: return modified_params def generate_config(self): - name = self.get_name() - model = self.get_model() - default_parameters = self.default_sensor_parameters[model]['ros__parameters'] + namespace = self.get_namespace() + node_key = list(self.default_sensor_parameters.keys())[0] + default_parameters = self.default_sensor_parameters[node_key]['ros__parameters'] parameters = { - name: { - 'ros__parameters': self.copy_parameters(default_parameters, self.sensor_parameters) + namespace: { + node_key: { + 'ros__parameters': self.copy_parameters(default_parameters, self.sensor_parameters) + } } } @@ -155,22 +155,26 @@ def __init__(self, sensor: BaseSensor, output_path: str = '/etc/clearpath/sensor self.generate_config() def generate_config(self): - name = self.get_name() - model = self.get_model() - default_driver_parameters = self.default_sensor_parameters[model + '_driver']['ros__parameters'] - default_pointcloud_parameters = self.default_sensor_parameters[model + '_pointcloud']['ros__parameters'] - default_laserscan_parameters = self.default_sensor_parameters[model + '_laserscan']['ros__parameters'] + namespace = self.get_namespace() + driver_key = 'velodyne_driver_node' + pointcloud_key = 'velodyne_convert_node' + laserscan_key = 'velodyne_laserscan_node' + default_driver_parameters = self.default_sensor_parameters[driver_key]['ros__parameters'] + default_pointcloud_parameters = self.default_sensor_parameters[pointcloud_key]['ros__parameters'] + default_laserscan_parameters = self.default_sensor_parameters[laserscan_key]['ros__parameters'] parameters = { - name + '_driver': { - 'ros__parameters': self.copy_parameters(default_driver_parameters, self.sensor_parameters) - }, - name + '_pointcloud': { - 'ros__parameters': self.copy_parameters(default_pointcloud_parameters, self.sensor_parameters) - }, - name + '_laserscan': { - 'ros__parameters': self.copy_parameters(default_laserscan_parameters, self.sensor_parameters) - }, + namespace: { + driver_key: { + 'ros__parameters': self.copy_parameters(default_driver_parameters, self.sensor_parameters) + }, + pointcloud_key: { + 'ros__parameters': self.copy_parameters(default_pointcloud_parameters, self.sensor_parameters) + }, + laserscan_key: { + 'ros__parameters': self.copy_parameters(default_laserscan_parameters, self.sensor_parameters) + }, + } } with open(self.sensor_parameters_file.get_full_path(), 'w+') as f: diff --git a/clearpath_sensors/config/hokuyo_ust10.yaml b/clearpath_sensors/config/hokuyo_ust10.yaml index 89344e2..3c2fbdd 100644 --- a/clearpath_sensors/config/hokuyo_ust10.yaml +++ b/clearpath_sensors/config/hokuyo_ust10.yaml @@ -1,4 +1,4 @@ -hokuyo_ust10: +urg_node: ros__parameters: angle_max: 3.14 angle_min: -3.14 diff --git a/clearpath_sensors/config/intel_realsense.yaml b/clearpath_sensors/config/intel_realsense.yaml index b21634b..ed97b6a 100644 --- a/clearpath_sensors/config/intel_realsense.yaml +++ b/clearpath_sensors/config/intel_realsense.yaml @@ -1,4 +1,4 @@ -intel_realsense: +camera: ros__parameters: camera_name: camera serial_no: '' diff --git a/clearpath_sensors/launch/hokuyo_ust10.launch.py b/clearpath_sensors/launch/hokuyo_ust10.launch.py index e64193b..e027d7a 100644 --- a/clearpath_sensors/launch/hokuyo_ust10.launch.py +++ b/clearpath_sensors/launch/hokuyo_ust10.launch.py @@ -7,15 +7,12 @@ def generate_launch_description(): - - name = LaunchConfiguration('name') parameters = LaunchConfiguration('parameters') namespace = LaunchConfiguration('namespace') - topic = LaunchConfiguration('topic') - arg_name = DeclareLaunchArgument( - 'name', - default_value='hokuyo_ust10') + arg_namespace = DeclareLaunchArgument( + 'namespace', + default_value='platform/sensors/lidar2d_0') arg_parameters = DeclareLaunchArgument( 'parameters', @@ -25,24 +22,16 @@ def generate_launch_description(): 'hokuyo_ust10.yaml' ])) - arg_topic = DeclareLaunchArgument( - 'topic', - default_value=[namespace, '/scan']) - urg_node = Node( package='urg_node', - name=name, + namespace=namespace, executable='urg_node_driver', - remappings=[ - ('scan', topic), - ], parameters=[parameters], output='screen', ) ld = LaunchDescription() - ld.add_action(arg_name) + ld.add_action(arg_namespace) ld.add_action(arg_parameters) - ld.add_action(arg_topic) ld.add_action(urg_node) return ld diff --git a/clearpath_sensors/launch/intel_realsense.launch.py b/clearpath_sensors/launch/intel_realsense.launch.py index 8c53912..b1e260f 100644 --- a/clearpath_sensors/launch/intel_realsense.launch.py +++ b/clearpath_sensors/launch/intel_realsense.launch.py @@ -7,14 +7,8 @@ def generate_launch_description(): - - name = LaunchConfiguration('name') parameters = LaunchConfiguration('parameters') - topic = LaunchConfiguration('topic') - - arg_name = DeclareLaunchArgument( - 'name', - default_value='intel_realsense') + namespace = LaunchConfiguration('namespace') arg_parameters = DeclareLaunchArgument( 'parameters', @@ -24,21 +18,20 @@ def generate_launch_description(): 'intel_realsense.yaml' ])) - arg_topic = DeclareLaunchArgument( - 'topic', - default_value='scan') + arg_namespace = DeclareLaunchArgument( + 'namespace', + default_value='platform/sensors/camera_0') realsense2_camera_node = Node( package='realsense2_camera', - name=name, + namespace=namespace, executable='realsense2_camera_node', parameters=[parameters], output='screen', ) ld = LaunchDescription() - ld.add_action(arg_name) ld.add_action(arg_parameters) - ld.add_action(arg_topic) + ld.add_action(arg_namespace) ld.add_action(realsense2_camera_node) return ld diff --git a/clearpath_sensors/launch/velodyne_lidar.launch.py b/clearpath_sensors/launch/velodyne_lidar.launch.py index fde8348..a8d0d6c 100644 --- a/clearpath_sensors/launch/velodyne_lidar.launch.py +++ b/clearpath_sensors/launch/velodyne_lidar.launch.py @@ -6,14 +6,13 @@ def generate_launch_description(): - name = LaunchConfiguration('name') + namespace = LaunchConfiguration('namespace') parameters = LaunchConfiguration('parameters') - topic = LaunchConfiguration('topic') velodyne_driver_node = Node( package='velodyne_driver', executable='velodyne_driver_node', - name=[name, '_driver'], + namespace=namespace, parameters=[parameters], output='screen' ) @@ -21,7 +20,7 @@ def generate_launch_description(): velodyne_pointcloud_node = Node( package='velodyne_pointcloud', executable='velodyne_convert_node', - name=[name, '_pointcloud'], + namespace=namespace, output='screen', parameters=[parameters] ) @@ -29,7 +28,7 @@ def generate_launch_description(): velodyne_laserscan_node = Node( package='velodyne_laserscan', executable='velodyne_laserscan_node', - name=[name, '_laserscan'], + namespace=namespace, output='screen', parameters=[parameters] )