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

Add the A200 Observer backpack attachment #96

Merged
merged 8 commits into from
Dec 5, 2024
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
13 changes: 13 additions & 0 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,3 +20,16 @@ jobs:
- uses: actions/checkout@v3
- uses: 'ros-industrial/industrial_ci@master'
env: ${{matrix.env}}

clearpath_config_src_ci:
name: Jazzy Clearpath Source
runs-on: ubuntu-24.04
steps:
- uses: actions/checkout@v3
- uses: ros-tooling/[email protected]
with:
required-ros-distributions: jazzy
- uses: ros-tooling/[email protected]
id: action_ros_ci_step
with:
target-ros2-distro: jazzy
1 change: 1 addition & 0 deletions clearpath_config/common/types/domain_id.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
class DomainID:

def __init__(self, _id: int = 0) -> None:
self.assert_valid(_id)
self.id = _id
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/common/types/file.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
# File
# - file class
class File:

def __init__(self, path: str, creatable=False, exists=False, make_abs=True) -> None:
if creatable:
assert File.is_creatable(path)
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/common/types/hostname.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
# Hostname
# - hostname class
class Hostname:

def __init__(self, hostname: str = 'hostname') -> None:
self.assert_valid(hostname)
self.hostname = hostname
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/common/types/ip.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
# IP
# - ip class
class IP:

def __init__(self, ip: str = '0.0.0.0') -> None:
self.assert_valid(ip)
self.ip_str = ip
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/common/types/port.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
# Port
# - TCP Port
class Port:

def __init__(self, port: int) -> None:
self.assert_valid(port)
self.port = int(port)
Expand Down
4 changes: 4 additions & 0 deletions clearpath_config/common/types/serial_number.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,10 @@ def parse(sn: str) -> tuple:
'cpr-j100-0001',
)
sn = sn[1:]
# Silently replace A201 prefix with A200
# Mechanically both are effectively identical, and re-use the same options & payloads
if sn[0] == 'a201':
sn[0] = 'a200'
# Match to Robot
assert sn[0] in Platform.ALL, (
'Serial Number model entry must match one of %s' % Platform.ALL
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/common/types/username.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

# Username
class Username:

def __init__(self, username: str = 'administrator') -> None:
self.assert_valid(username)
self.username = username
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/links/links.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ def __new__(cls, _type: str, name: str) -> BaseLink:

# LinkListConfig
class LinkListConfig(ListConfig[BaseLink, str]):

def __init__(self) -> None:
super().__init__(
uid=lambda obj: obj.get_name(),
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/mounts/mounts.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ def __new__(cls, model: str) -> BaseMount:


class MountListConfig(OrderedListConfig[BaseMount]):

def __init__(self) -> None:
super().__init__(obj_type=BaseMount)

Expand Down
23 changes: 23 additions & 0 deletions clearpath_config/platform/attachments/a200.py
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,26 @@ def __init__(
super().__init__(name, model, enabled, parent, xyz, rpy)


class A200ObserverBackpack(BaseAttachment):
PLATFORM = Platform.A200
ATTACHMENT_MODEL = '%s.observer_backpack' % PLATFORM
OBSERVER_BACKPACK = 'observer_backpack'
MODELS = [OBSERVER_BACKPACK]
DEFAULT = OBSERVER_BACKPACK
PARENT = 'default_mount'

def __init__(
self,
name: str = ATTACHMENT_MODEL,
model: str = DEFAULT,
enabled: bool = BaseAttachment.ENABLED,
parent: str = PARENT,
xyz: List[float] = Accessory.XYZ,
rpy: List[float] = Accessory.RPY
) -> None:
super().__init__(name, model, enabled, parent, xyz, rpy)


class A200Attachment(PlatformAttachment):
PLATFORM = Platform.A200
# Top Plates
Expand All @@ -105,9 +125,12 @@ class A200Attachment(PlatformAttachment):
BUMPER = A200Bumper.ATTACHMENT_MODEL
# Archs
SENSOR_ARCH = A200SensorArch.ATTACHMENT_MODEL
# Observer Backpack
OBSERVER_BACKPACK = A200ObserverBackpack.ATTACHMENT_MODEL

TYPES = {
TOP_PLATE: A200TopPlate,
BUMPER: A200Bumper,
SENSOR_ARCH: A200SensorArch,
OBSERVER_BACKPACK: A200ObserverBackpack,
}
2 changes: 2 additions & 0 deletions clearpath_config/platform/attachments/config.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@


class AttachmentListConfig(ListConfig[BaseAttachment, str]):

def __init__(self) -> None:
super().__init__(
uid=lambda obj: obj.get_name(),
Expand All @@ -50,6 +51,7 @@ def to_dict(self) -> dict:
# Attachments Config
# - to be used by all platforms.
class AttachmentsConfig:

def __init__(
self,
attachment,
Expand Down
1 change: 1 addition & 0 deletions clearpath_config/platform/can.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,7 @@ def interface(self, interface: str) -> None:


class CANBridgeListConfig(ListConfig[CANBridge, str]):

def __init__(self) -> None:
super().__init__(
uid=lambda obj: obj.interface,
Expand Down
146 changes: 146 additions & 0 deletions clearpath_config/sample/a200/a200_observer.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,146 @@
serial_number: a201-0000
version: 0
system:
hosts:
- hostname: cpr-a201-0000
ip: 192.168.131.1
ros2:
namespace: a201_0000
platform:
attachments:
- name: front_bumper
type: a200.bumper
parent: front_bumper_mount
- name: rear_bumper
type: a200.bumper
parent: rear_bumper_mount
- name: backpack
type: a200.observer_backpack
sensors:
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: backpack_front_lidar_mount
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.21
ip_port: 10940
angle_min: -1.5707963267948966
angle_max: 1.5707963267948966
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: backpack_rear_lidar_mount
ros_parameters:
urg_node:
laser_frame_id: lidar2d_1_laser
ip_address: 192.168.131.22
ip_port: 10940
angle_min: -1.5707963267948966
angle_max: 1.5707963267948966
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: backpack_center_lidar_mount
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.20
port: 2368
model: VLP16
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
camera:
- model: intel_realsense
parent: backpack_front_realsense_mount
ros_parameters:
intel_realsense:
camera_name: camera_0
device_type: d435
serial_no: "1234567890"
- model: intel_realsense
parent: backpack_rear_realsense_mount
ros_parameters:
intel_realsense:
camera_name: camera_1
device_type: d435
serial_no: "9876543210"
- model: axis_camera
parent: backpack_center_mount
ros_parameters:
axis_camera:
device_type: q62
hostname: "192.168.131.10"
http_port: 80
username: "root"
password: ""
width: 640
height: 480
fps: 20
tf_prefix: "axis"
camera_info_url: ""
use_encrypted_password : False
camera : 1
ir: True
defog: True
wiper: True
ptz: True
min_pan: -3.141592653589793
max_pan: 3.141592653589793
min_tilt: 0.0
max_tilt: 1.5707963267948966
min_zoom: 1
max_zoom: 24
max_pan_speed: 2.61
max_tilt_speed: 2.61
ptz_teleop: True
button_enable_pan_tilt : -1
button_enable_zoom : -1
axis_pan : 3
axis_tilt : 4
invert_tilt : False
axis_zoom_in: 5
axis_zoom_out: 2
zoom_in_offset: -1.0
zoom_out_offset: -1.0
zoom_in_scale: -0.5
zoom_out_scale: 0.5
scale_pan : 2.61
scale_tilt : 2.61
scale_zoom : 100.0
gps:
- model: swiftnav_duro
urdf_enabled: true
launch_enabled: true
parent: backpack_right_antenna_mount
ros_parameters:
duro_node:
gps_receiver_frame_id: gps_0_link
ip_address: 192.168.131.31
ip_port: 55555
imu_frame_id: gps_0_link
- model: swiftnav_duro
urdf_enabled: true
launch_enabled: true
parent: backpack_left_antenna_mount
ros_parameters:
duro_node:
gps_receiver_frame_id: gps_1_link
ip_address: 192.168.131.32
ip_port: 55555
imu_frame_id: gps_1_link
imu:
- model: microstrain_imu
urdf_enabled: true
launch_enabled: true
parent: backpack_imu_mount
ros_parameters:
microstrain_inertial_driver:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
1 change: 1 addition & 0 deletions clearpath_config/sensors/sensors.py
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,7 @@ def __new__(cls, _type: str, _model: str) -> BaseSensor:


class SensorListConfig(OrderedListConfig[BaseSensor]):

def __init__(self) -> None:
super().__init__(obj_type=BaseSensor)

Expand Down
1 change: 1 addition & 0 deletions clearpath_config/system/servers.py
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 +194,7 @@ def enabled(self, value: bool) -> None:

# LinkListConfig
class ServerListConfig(ListConfig[ServerConfig, int]):

def __init__(self) -> None:
super().__init__(
uid=lambda obj: obj.server_id,
Expand Down