Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Renamed ust10 to ust #29

Merged
merged 3 commits into from
Aug 2, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions clearpath_config/sample/a200/a200_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ sensors:
port: /dev/microstrain_main
use_enu_frame: true
lidar2d:
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: top_plate_mount_d1
Expand All @@ -81,7 +81,7 @@ sensors:
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: top_plate_mount_d8
Expand Down
2 changes: 1 addition & 1 deletion clearpath_config/sample/a200/a200_sample.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ sensors:
gps: []
imu: []
lidar2d:
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_0_mount
Expand Down
4 changes: 2 additions & 2 deletions clearpath_config/sample/j100/j100_dual_laser.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ sensors:
gps: []
imu: []
lidar2d:
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: front_mount
Expand All @@ -65,7 +65,7 @@ sensors:
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: rear_mount
Expand Down
4 changes: 2 additions & 2 deletions clearpath_config/sample/j100/j100_sample.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ sensors:
gps: []
imu: []
lidar2d:
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_0_mount
Expand All @@ -74,7 +74,7 @@ sensors:
ip_port: 10940
angle_min: -3.141592653589793
angle_max: 3.141592653589793
- model: hokuyo_ust10
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_1_mount
Expand Down
50 changes: 25 additions & 25 deletions clearpath_config/sensors/sensors.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
)
from clearpath_config.sensors.types.lidars_2d import (
BaseLidar2D,
HokuyoUST10,
HokuyoUST,
SickLMS1XX,
)
from clearpath_config.sensors.types.lidars_3d import (
Expand Down Expand Up @@ -137,11 +137,11 @@ def __new__(cls, model: str) -> BaseGPS:


class Lidar2D():
HOKUYO_UST10 = HokuyoUST10.SENSOR_MODEL
HOKUYO_UST = HokuyoUST.SENSOR_MODEL
SICK_LMS1XX = SickLMS1XX.SENSOR_MODEL

MODEL = {
HOKUYO_UST10: HokuyoUST10,
HOKUYO_UST: HokuyoUST,
SICK_LMS1XX: SickLMS1XX
}

Expand Down Expand Up @@ -461,25 +461,25 @@ def add_lidar2d(
lidar2d.set_rpy(rpy)
self._lidar2d.add(lidar2d)

# Lidar2D: Add UST10
def add_ust10(
# Lidar2D: Add UST
def add_ust(
self,
# By Object
ust10: HokuyoUST10 = None,
ust: HokuyoUST = None,
# By Parameters
frame_id: str = HokuyoUST10.FRAME_ID,
ip: str = HokuyoUST10.IP_ADDRESS,
port: int = HokuyoUST10.IP_PORT,
min_angle: float = HokuyoUST10.MIN_ANGLE,
max_angle: float = HokuyoUST10.MAX_ANGLE,
urdf_enabled: bool = HokuyoUST10.URDF_ENABLED,
launch_enabled: bool = HokuyoUST10.LAUNCH_ENABLED,
frame_id: str = HokuyoUST.FRAME_ID,
ip: str = HokuyoUST.IP_ADDRESS,
port: int = HokuyoUST.IP_PORT,
min_angle: float = HokuyoUST.MIN_ANGLE,
max_angle: float = HokuyoUST.MAX_ANGLE,
urdf_enabled: bool = HokuyoUST.URDF_ENABLED,
launch_enabled: bool = HokuyoUST.LAUNCH_ENABLED,
parent: str = Accessory.PARENT,
xyz: List[float] = Accessory.XYZ,
rpy: List[float] = Accessory.RPY
) -> None:
if ust10 is None:
ust10 = HokuyoUST10(
if ust is None:
ust = HokuyoUST(
frame_id=frame_id,
ip=ip,
port=port,
Expand All @@ -491,10 +491,10 @@ def add_ust10(
xyz=xyz,
rpy=rpy
)
assert isinstance(ust10, HokuyoUST10), (
"Lidar2D object must be of type UST10"
assert isinstance(ust, HokuyoUST), (
"Lidar2D object must be of type UST"
)
self._lidar2d.add(ust10)
self._lidar2d.add(ust)

# Lidar2D: Add LMS1xx
def add_lms1xx(
Expand Down Expand Up @@ -552,9 +552,9 @@ def get_all_lidar_2d_by_model(self, model: str) -> List[BaseLidar2D]:
all_model_lidar_2d.append(lidar_2d)
return all_model_lidar_2d

# Lidar2D: Get All Objects of Model UST10
def get_all_ust10(self) -> List[HokuyoUST10]:
return self.get_all_lidar_2d_by_model(Lidar2D.UST10)
# Lidar2D: Get All Objects of Model UST
def get_all_ust(self) -> List[HokuyoUST]:
return self.get_all_lidar_2d_by_model(Lidar2D.UST)

# Lidar2D: Get All Objects of Model LMS1XX
def get_all_lms1xx(self) -> List[SickLMS1XX]:
Expand Down Expand Up @@ -653,7 +653,7 @@ def get_all_lidar_3d_by_model(self, model: str) -> List[BaseLidar3D]:
all_model_lidar_3d.append(lidar_3d)
return all_model_lidar_3d

# Lidar3D: Get All Objects of Model UST10
# Lidar3D: Get All Objects of Model UST
def get_all_velodyne(self) -> List[VelodyneLidar]:
return self.get_all_lidar_3d_by_model(Lidar3D.VELODYNE_LIDAR)

Expand Down Expand Up @@ -807,7 +807,7 @@ def get_all_cameras_by_model(self, model: str) -> List[BaseCamera]:
all_model_camera.append(camera)
return all_model_camera

# Camera: Get All Objects of Model UST10
# Camera: Get All Objects of Model UST
def get_all_realsense(self) -> List[IntelRealsense]:
return self.get_all_cameras_by_model(Camera.INTEL_REALSENSE)

Expand Down Expand Up @@ -965,7 +965,7 @@ def add_duro(
rpy=rpy
)
assert isinstance(duro, SwiftNavDuro), (
"GPS object must be of type UST10"
"GPS object must be of type UST"
)
self._gps.add(duro)

Expand All @@ -990,7 +990,7 @@ def get_all_gps_by_model(self, model: str) -> List[BaseGPS]:
all_model_gps.append(gps)
return all_model_gps

# GPS: Get All Objects of Model UST10
# GPS: Get All Objects of Model UST
def get_all_duro(self) -> List[SwiftNavDuro]:
return self.get_all_gps_by_model(
GlobalPositioningSystem.SWIFTNAV_DURO)
Expand Down
4 changes: 2 additions & 2 deletions clearpath_config/sensors/types/lidars_2d.py
Original file line number Diff line number Diff line change
Expand Up @@ -209,8 +209,8 @@ def set_max_angle(self, angle: float) -> None:
self.max_angle = angle


class HokuyoUST10(BaseLidar2D):
SENSOR_MODEL = "hokuyo_ust10"
class HokuyoUST(BaseLidar2D):
SENSOR_MODEL = "hokuyo_ust"

FRAME_ID = "laser"
IP_PORT = 10940
Expand Down