Skip to content

Commit

Permalink
Updated samples
Browse files Browse the repository at this point in the history
  • Loading branch information
luis-camero committed Aug 1, 2023
1 parent 26f2ef6 commit c804534
Show file tree
Hide file tree
Showing 9 changed files with 121 additions and 120 deletions.
51 changes: 15 additions & 36 deletions clearpath_config/platform/extras.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,12 +86,10 @@ def __new__(cls, platform: str) -> dict:

# ExtrasConfig:
# - URDF extras: urdf.xacro with custom links and joints
# - Control extras: YAML with overwrites or extra ROS parameters
class ExtrasConfig(BaseConfig):

EXTRAS = "extras"
URDF = "urdf"
CONTROL = "control"
ROS_PARAMETERS = "ros_parameters"

PLATFORM_VELOCITY_CONTROLLER = "platform_velocity_controller"
Expand All @@ -108,7 +106,6 @@ class ExtrasConfig(BaseConfig):
TEMPLATE = {
EXTRAS: {
URDF: URDF,
CONTROL: CONTROL,
ROS_PARAMETERS: {
PLATFORM_VELOCITY_CONTROLLER: {
WHEEL_RADIUS: WHEEL_RADIUS,
Expand All @@ -130,15 +127,13 @@ class ExtrasConfig(BaseConfig):

DEFAULTS = {
URDF: "empty.urdf.xacro",
CONTROL: "empty.yaml",
ROS_PARAMETERS: ROSParamaterDefaults(BaseConfig.get_platform_model()),
}

def __init__(
self,
config: dict = {},
urdf: str = DEFAULTS[URDF],
control: str = DEFAULTS[CONTROL],
ros_parameters: dict = {},
) -> None:
# ROS Parameter Setter Template
Expand All @@ -156,30 +151,19 @@ def __init__(
# Setter Template
self.setters = {
self.KEYS[self.URDF]: ExtrasConfig.urdf,
self.KEYS[self.CONTROL]: ExtrasConfig.control,
self.KEYS[self.ROS_PARAMETERS]: ExtrasConfig.ros_parameters,
}
# Initialization
self.init_ros_parameter()
self._init_ros_parameter()
self._config = {}
self.urdf = urdf
self.control = control
self.ros_parameters = ros_parameters
# Set from Config
super().__init__(self.setters, config, self.EXTRAS)

def update(self, serial_number: bool = False) -> None:
if serial_number:
defaults = flatten_dict(ROSParamaterDefaults(self.get_platform_model()))
previous = flatten_dict(self.DEFAULTS[self.ROS_PARAMETERS])
rosparam = flatten_dict(self.ros_parameters)
for key, val in rosparam.items():
if key in previous:
if rosparam[key] == previous[key] and (
key in defaults):
rosparam[key] = defaults[key]
self.DEFAULTS[self.ROS_PARAMETERS] = ROSParamaterDefaults(self.get_platform_model())
self.ros_parameters = rosparam
self._update_ros_parameter()

@property
def urdf(self) -> str:
Expand All @@ -196,40 +180,32 @@ def urdf(self, value: str) -> None:
return
self._urdf = File(path=str(value))

@property
def control(self) -> str:
control = None if self._is_default(self._control, self.CONTROL) else str(self._control)
return control

@control.setter
def control(self, value: str) -> None:
if value is None or value == "None":
return
self._control = File(path=str(value))

def _is_default(self, curr: str, key: str) -> bool:
return curr == str(File(self.DEFAULTS[key]))

def is_ros_parameter_default(self, key) -> bool:
def _is_ros_parameter(self, key) -> bool:
return any([key in i for i in self._ros_parameters_setters])

def _is_ros_parameter_default(self, key) -> bool:
default_parameters = self.DEFAULTS[self.ROS_PARAMETERS]
current_val = self.getter(self._ros_parameters_setters[key])()
default_val = flatten_dict(default_parameters)[".".join(key.split(".")[2:])]
return current_val == default_val

def init_ros_parameter(self) -> None:
def _init_ros_parameter(self) -> None:
default_parameters = self.DEFAULTS[self.ROS_PARAMETERS]
for _, extended_key in self.KEYS.items():
if extended_key in self._ros_parameters_setters:
default_parameters_key = ".".join(extended_key.split(".")[2:])
setter = self.setter(self._ros_parameters_setters[extended_key])
setter(default_parameters[default_parameters_key])

def update_ros_parameter(self) -> None:
def _update_ros_parameter(self) -> None:
default_parameters = ROSParamaterDefaults(self.get_platform_model())
for _, extended_key in self.KEYS.items():
if extended_key in self._ros_parameters_setters:
default_parameters_key = ".".join(extended_key.split(".")[2:])
if not self.is_ros_parameter_default(extended_key):
if not self._is_ros_parameter_default(extended_key):
continue
setter = self.setter(self._ros_parameters_setters[extended_key])
setter(default_parameters[default_parameters_key])
Expand All @@ -238,12 +214,15 @@ def update_ros_parameter(self) -> None:
"""ROS parameters with node names and flattened dictionaries"""
@property
def ros_parameters(self) -> dict:
# Add all user values
d = flatten_dict(self._ros_parameters)
d = {}
# Add non-default values
for key, prop in self._ros_parameters_setters.items():
if not self.is_ros_parameter_default(key):
if not self._is_ros_parameter_default(key):
d[".".join(key.split(".")[2:])] = self.getter(prop)()
# User parameters
for key, val, in self._ros_parameters.items():
if not self._is_ros_parameter(key):
d[key] = val
# Return flat
d = unflatten_dict(d)
for node_name in d:
Expand Down
2 changes: 1 addition & 1 deletion clearpath_config/sample/a200/a200_default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ platform:
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
control: null
ros_parameters: {}
links:
box: []
cylinder: []
Expand Down
41 changes: 22 additions & 19 deletions clearpath_config/sample/a200/a200_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ platform:
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
control: null
ros_parameters: {}
links:
box: []
cylinder: []
Expand All @@ -61,32 +61,35 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
microstrain_inertial_driver:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
lidar2d:
- model: sick_lms1xx
- model: hokuyo_ust10
urdf_enabled: true
launch_enabled: true
parent: base_link
parent: top_plate_mount_d1
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
frame_id: lidar2d_0_laser
hostname: 192.168.131.20
port: 2112
min_ang: -2.391
max_ang: 2.391
- model: sick_lms1xx
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
- model: hokuyo_ust10
urdf_enabled: true
launch_enabled: true
parent: base_link
parent: top_plate_mount_d8
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 3.1415]
ros_parameters:
frame_id: lidar2d_1_laser
hostname: 192.168.131.21
port: 2112
min_ang: -2.391
max_ang: 2.391
urg_node:
laser_frame_id: lidar2d_1_laser
ip_address: 192.168.131.21
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
lidar3d: []
43 changes: 24 additions & 19 deletions clearpath_config/sample/a200/a200_sample.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -72,14 +72,15 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
camera_name: camera_0
device_type: d435
serial_no: '0'
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true
camera:
camera_name: camera_0
device_type: d435
serial_no: '0'
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true
gps: []
imu: []
lidar2d:
Expand All @@ -90,11 +91,12 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
Expand All @@ -103,9 +105,12 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
24 changes: 14 additions & 10 deletions clearpath_config/sample/a200/a200_velodyne.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ platform:
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
control: null
ros_parameters: {}
links:
box: []
cylinder: []
Expand All @@ -61,9 +61,10 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
microstrain_inertial_driver:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
lidar2d: []
lidar3d:
- model: velodyne_lidar
Expand All @@ -73,9 +74,12 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_convert_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
2 changes: 1 addition & 1 deletion clearpath_config/sample/j100/j100_default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ platform:
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
control: null
ros_parameters: {}
links:
box: []
cylinder: []
Expand Down
22 changes: 12 additions & 10 deletions clearpath_config/sample/j100/j100_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -57,21 +57,23 @@ sensors:
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
- model: hokuyo_ust10
urdf_enabled: true
launch_enabled: true
parent: rear_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 3.1415]
ros_parameters:
laser_frame_id: lidar2d_1_laser
ip_address: 192.168.131.21
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
urg_node:
laser_frame_id: lidar2d_1_laser
ip_address: 192.168.131.21
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
lidar3d: []
Loading

0 comments on commit c804534

Please sign in to comment.