Skip to content

Add A300 Observer attachments #200

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

Merged
merged 19 commits into from
Jun 4, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
b6b3226
Add meshes, URDFs for the A300 Observer attachments. Waiting for fina…
civerachb-cpr Apr 9, 2025
0ee76a8
Add placeholders for the front & rear face sensor mounts
civerachb-cpr Apr 9, 2025
0b37829
Add sensor mount points from Rhys
civerachb-cpr Apr 10, 2025
e942bcf
Fix the angle of the rear camera mount, rear INS. Remove duplicate li…
civerachb-cpr Apr 10, 2025
956e013
Add the ability to specify the OS-1 cap type & omit the base plate
civerachb-cpr Apr 10, 2025
a806ffc
Add spotlight attachment with light plugin for simulation
civerachb-cpr Apr 14, 2025
e29ab5c
Don't render the light sources
civerachb-cpr Apr 14, 2025
9615f44
Increase the angles of the spotlights
civerachb-cpr Apr 17, 2025
47d6dc3
Fix gazebo link tag
civerachb-cpr Apr 22, 2025
719ba9b
Make parameters easier to read, update angle, resolution
civerachb-cpr Apr 22, 2025
017695c
Add Seyond description with lower-than-reality resolution & correct F…
civerachb-cpr Apr 22, 2025
8a31dde
Add GPS plugins for the Fixposition description
civerachb-cpr Apr 22, 2025
04cb724
Add new URDFs from Rhys, add cellular & wifi antennas to the observer…
civerachb-cpr Jun 3, 2025
2a7d41e
Add a link to the face of the charger, as this may be useful for docking
civerachb-cpr Jun 3, 2025
d7f1084
Rotate the charger face link so the X axis points outward
civerachb-cpr Jun 3, 2025
f3b029d
Merge all arch antennas into a single frame, put an oversized box col…
civerachb-cpr Jun 4, 2025
3452f8e
Remove the old AMP arch; AMP & Observer use the same arch. Observer -…
civerachb-cpr Jun 4, 2025
8ee9418
Use a box collider for the wireless charger
civerachb-cpr Jun 4, 2025
676c314
0. -> 0.0
civerachb-cpr Jun 4, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
from typing import List

from clearpath_config.platform.attachments.a200 import A200Attachment
from clearpath_config.platform.attachments.a300 import A300Attachment
from clearpath_config.platform.attachments.config import BaseAttachment
from clearpath_config.platform.attachments.dd100 import DD100Attachment
from clearpath_config.platform.attachments.dd150 import DD150Attachment
Expand Down Expand Up @@ -125,6 +126,12 @@ def __init__(self, attachment: BaseAttachment) -> None:
A200Attachment.TOP_PLATE: BaseDescription,
A200Attachment.SENSOR_ARCH: BaseDescription,
A200Attachment.OBSERVER_BACKPACK: BaseDescription,
# A300
A300Attachment.BUMPER: BumperDescription,
A300Attachment.TOP_PLATE: BaseDescription,
A300Attachment.AMP_SENSOR_ARCH: BaseDescription,
A300Attachment.AMP_ENCLOSURE: BaseDescription,
A300Attachment.SPOTLIGHT: BaseDescription,
# J100
J100Attachment.FENDER: BaseDescription,
J100Attachment.TOP_PLATE: BaseDescription,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -193,15 +193,36 @@ def __init__(self, sensor: BaseINS) -> None:
class OusterOS1Description(Lidar3dDescription):
SAMPLES_HORIZONTAL = 'samples_h'
SAMPLES_VERTICAL = 'samples_v'
BASE_TYPE = 'base'
CAP_TYPE = 'cap'

def __init__(self, sensor: BaseLidar3D) -> None:
def __init__(self, sensor: OusterOS1) -> None:
super().__init__(sensor)

del self.parameters[self.ANGULAR_RESOLUTION_H]
del self.parameters[self.ANGULAR_RESOLUTION_V]
self.parameters.update({
self.SAMPLES_HORIZONTAL: 1024,
self.SAMPLES_VERTICAL: 64
self.SAMPLES_VERTICAL: 64,
self.BASE_TYPE: sensor.base_type,
self.CAP_TYPE: sensor.cap_type,
})

class SeyondLidarDescription(Lidar3dDescription):

def __init__(self, sensor: BaseLidar3D) -> None:
super().__init__(sensor)

self.parameters.update({
self.ANGULAR_RESOLUTION_H: 0.01,
self.ANGULAR_RESOLUTION_V: 0.01,
self.MINIMUM_ANGLE_H: -1.0471975511965976,
self.MAXIMUM_ANGLE_H: 1.0471975511965976,
self.MINIMUM_ANGLE_V: -0.6108652381980153,
self.MAXIMUM_ANGLE_V: 0.6108652381980153,
self.MINIMUM_RANGE: 0.1,
self.MAXIMUM_RANGE: 150.0,
self.UPDATE_RATE: 20 # TODO: link to clearpath_config property
})

class ImuDescription(BaseDescription):
Expand Down Expand Up @@ -276,7 +297,7 @@ def __init__(self, sensor: StereolabsZed) -> None:
AxisCamera.SENSOR_MODEL: AxisCameraDescription,
Microstrain.SENSOR_MODEL: ImuDescription,
OusterOS1.SENSOR_MODEL: OusterOS1Description,
SeyondLidar.SENSOR_MODEL: Lidar3dDescription,
SeyondLidar.SENSOR_MODEL: SeyondLidarDescription,
VelodyneLidar.SENSOR_MODEL: Lidar3dDescription,
CHRoboticsUM6.SENSOR_MODEL: ImuDescription,
RedshiftUM7.SENSOR_MODEL: ImuDescription,
Expand Down
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org.xacro">
<xacro:macro name="amp_enclosure" params="name parent_link:=base_link model:=amp_enclosure *origin">
<link name="${name}_enclosure_link">
<visual>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_enclosure.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="dark_grey"><color rgba="0.1 0.1 0.1 1.0" /></material>
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<collision>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_enclosure.stl" scale="0.001 0.001 0.001" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
</link>
<gazebo reference="${name}_enclosure_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="${name}_enclosure_joint" type="fixed">
<parent link="${parent_link}" />
<child link="${name}_enclosure_link" />
<xacro:insert_block name="origin"/>
</joint>

<link name="${name}_access_panels_link">
<visual>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_access_panels.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="yellow"><color rgba="1 0.6038269 0 1.0" /></material>
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
</link>
<joint name="${name}_access_panels_joint" type="fixed">
<parent link="${name}_enclosure_link" />
<child link="${name}_access_panels_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<gazebo reference="${name}_access_panels_link">
<material>Gazebo/DarkYellow</material>
</gazebo>

<!--
Mount points for sensors, other accessories
-->

<!-- center of the adjustable track on top -->
<link name="${name}_center_mount" />
<joint name="${name}_center_joint" type="fixed">
<parent link="${name}_enclosure_link" />
<child link="${name}_center_mount" />
<origin xyz="0 0 0.4074593" rpy="0 0 0" />
</joint>

<!-- standard rear-mounted antennas -->
<link name="${name}_antenna_mount" />
<joint name="${name}_antenna_mount_link" type="fixed">
<parent link="${name}_enclosure_link" />
<child link="${name}_antenna_mount" />
<origin xyz="-0.4028 0 0.4074593" rpy="0 0 0" />
</joint>

<!-- rear-mounted fixposition -->
<link name="${name}_ins_mount" />
<joint name="${name}_ins_mouint_link" type="fixed">
<parent link="${name}_enclosure_link" />
<child link="${name}_ins_mount" />
<origin xyz="-0.4 0.0 0.3192593" rpy="3.14159 0 3.14159" />
</joint>

<!-- front-mounted robin -->
<link name="${name}_front_lidar_mount" />
<joint name="${name}_front_lidar_mount_link" type="fixed">
<parent link="${name}_enclosure_link" />
<child link="${name}_front_lidar_mount" />
<origin xyz="0.40 0 0.2708593" rpy="0 0 0" />
</joint>
</xacro:macro>
</robot>

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org.xacro">
<xacro:macro name="amp_sensor_arch" params="name parent_link:=default_mount model:=amp_sensor_arch *origin">

<!--
Main sensor arch
-->
<link name="${name}_link">
<visual>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_arch.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="yellow"><color rgba="0.8 0.8 0.0 1.0" /></material>
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<collision>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_arch.stl" scale="0.001 0.001 0.001" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
</link>
<gazebo reference="${name}_link">
<material>Gazebo/DarkYellow</material>
</gazebo>
<joint name="${name}_joint" type="fixed">
<parent link="${parent_link}" />
<child link="${name}_link" />
<xacro:insert_block name="origin"/>
</joint>

<!--
Standard antennas & accessories
-->
<link name="${name}_antennas">
<visual>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_cellular_antenna.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="clearpath_black" />
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<visual>
<geometry>
<mesh filename="package://clearpath_platform_description/meshes/a300/attachments/observer_wifi_antennas.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="clearpath_black" />
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<collision>
<geometry>
<box size="0.170 0.350 0.12" />
</geometry>
<material name="clearpath_black" />
<origin xyz="0 0 0.490" rpy="0 0 0" />
</collision>
</link>
<joint name="${name}_antennas_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_antennas" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<!--
Sensor mounting points
-->

<link name="${name}_left_antenna_mount" />
<joint name="${name}_left_antenna_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_left_antenna_mount" />
<origin xyz="0 0.260 0.44536" rpy="0 0 0" />
</joint>

<link name="${name}_right_antenna_mount" />
<joint name="${name}_right_antenna_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_right_antenna_mount" />
<origin xyz="0 -0.260 0.44536" rpy="0 0 0" />
</joint>

<link name="${name}_lidar_mount" />
<joint name="${name}_lidar_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_lidar_mount" />
<origin xyz="0.130 0 0.30256" rpy="3.14159 0 0" />
</joint>

<!-- front-facing camera suspended under sensor arch -->
<link name="${name}_front_camera_mount" />
<joint name="${name}_front_camera_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_front_camera_mount" />
<origin xyz="0.0775 0 0.40896" rpy="0 0 0" />
</joint>

<!-- rear-facing camera suspended under sensor arch -->
<link name="${name}_rear_camera_mount" />
<joint name="${name}_rear_camera_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_rear_camera_mount" />
<origin xyz="-0.09053483924399536 0 0.39093965966919125" rpy="0 0.6021385919380436 3.14159" />
</joint>

<!-- corner mounts for lights, etc... -->
<link name="${name}_front_left_corner_mount" />
<joint name="${name}_front_left_corner_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_front_left_corner_mount" />
<origin xyz="0.07 0.310 0.44536" rpy="0 0 0" />
</joint>
<link name="${name}_front_right_corner_mount" />
<joint name="${name}_front_right_corner_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_front_right_corner_mount" />
<origin xyz="0.07 -0.310 0.44536" rpy="0 0 0" />
</joint>
<link name="${name}_rear_left_corner_mount" />
<joint name="${name}_rear_left_corner_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_rear_left_corner_mount" />
<origin xyz="-0.07 0.310 0.44536" rpy="0 0 3.14159" />
</joint>
<link name="${name}_rear_right_corner_mount" />
<joint name="${name}_rear_right_corner_mount_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_rear_right_corner_mount" />
<origin xyz="-0.07 -0.310 0.44536" rpy="0 0 3.14159" />
</joint>

</xacro:macro>
</robot>
Loading
Loading