Skip to content

Commit

Permalink
Merge pull request #34 from clearpathrobotics/node_names
Browse files Browse the repository at this point in the history
Updated config to match changes
  • Loading branch information
tonybaltovski authored Sep 29, 2023
2 parents 6a4063f + 026b0c1 commit 3c89f83
Show file tree
Hide file tree
Showing 10 changed files with 22 additions and 30 deletions.
3 changes: 1 addition & 2 deletions clearpath_config/sample/a200/a200_default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down
3 changes: 1 addition & 2 deletions clearpath_config/sample/a200/a200_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down
5 changes: 2 additions & 3 deletions clearpath_config/sample/a200/a200_sample.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down Expand Up @@ -123,7 +122,7 @@ sensors:
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
5 changes: 2 additions & 3 deletions clearpath_config/sample/a200/a200_velodyne.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down Expand Up @@ -92,7 +91,7 @@ sensors:
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
3 changes: 1 addition & 2 deletions clearpath_config/sample/j100/j100_default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: j100_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down
3 changes: 1 addition & 2 deletions clearpath_config/sample/j100/j100_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: j100_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down
5 changes: 2 additions & 3 deletions clearpath_config/sample/j100/j100_sample.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: j100_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down Expand Up @@ -104,7 +103,7 @@ sensors:
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
5 changes: 2 additions & 3 deletions clearpath_config/sample/j100/j100_velodyne.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ system:
namespace: j100_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces:
- /home/administrator/micro_ros_ws/install/setup.bash
workspaces: []
platform:
controller: ps4
attachments:
Expand Down Expand Up @@ -64,7 +63,7 @@ sensors:
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
12 changes: 6 additions & 6 deletions clearpath_config/sensors/types/lidars_2d.py
Original file line number Diff line number Diff line change
Expand Up @@ -265,16 +265,16 @@ class SickLMS1XX(BaseLidar2D):
SENSOR_MODEL = "sick_lms1xx"

FRAME_ID = "laser"
IP_PORT = 2112
IP_PORT = 2111
MIN_ANGLE = -2.391
MAX_ANGLE = 2.391

class ROS_PARAMETER_KEYS:
FRAME_ID = "sick_scan.frame_id"
IP_ADDRESS = "sick_scan.hostname"
IP_PORT = "sick_scan.port"
MIN_ANGLE = "sick_scan.min_ang"
MAX_ANGLE = "sick_scan.max_ang"
FRAME_ID = "lms1xx.frame_id"
IP_ADDRESS = "lms1xx.host"
IP_PORT = "lms1xx.port"
MIN_ANGLE = "lms1xx.min_ang"
MAX_ANGLE = "lms1xx.max_ang"

def __init__(
self,
Expand Down
8 changes: 4 additions & 4 deletions clearpath_config/sensors/types/lidars_3d.py
Original file line number Diff line number Diff line change
Expand Up @@ -188,9 +188,9 @@ class ROS_PARAMETER_KEYS:
IP_ADDRESS = "velodyne_driver_node.device_ip"
IP_PORT = "velodyne_driver_node.port"
DRIVER_NODE_MODEL = "velodyne_driver_node.model"
CONVERT_NODE_MODEL = "velodyne_convert_node.model"
FIXED_FRAME = "velodyne_convert_node.fixed_frame"
TARGET_FRAME = "velodyne_convert_node.target_frame"
TRANSFORM_NODE_MODEL = "velodyne_transform_node.model"
FIXED_FRAME = "velodyne_transform_node.fixed_frame"
TARGET_FRAME = "velodyne_transform_node.target_frame"

def __init__(
self,
Expand All @@ -213,7 +213,7 @@ def __init__(
# ROS Parameter Template
ros_parameters_template = {
self.ROS_PARAMETER_KEYS.DRIVER_NODE_MODEL: VelodyneLidar.device_type,
self.ROS_PARAMETER_KEYS.CONVERT_NODE_MODEL: VelodyneLidar.device_type,
self.ROS_PARAMETER_KEYS.TRANSFORM_NODE_MODEL: VelodyneLidar.device_type,
self.ROS_PARAMETER_KEYS.FIXED_FRAME: VelodyneLidar.frame_id,
self.ROS_PARAMETER_KEYS.TARGET_FRAME: VelodyneLidar.frame_id,
}
Expand Down

0 comments on commit 3c89f83

Please sign in to comment.