Skip to content

Commit

Permalink
feat(aip_xx1_description): add radar description to xx1
Browse files Browse the repository at this point in the history
Signed-off-by: Shunsuke Miura <[email protected]>
  • Loading branch information
miursh committed Jul 25, 2023
1 parent 6d66089 commit 7c118dc
Show file tree
Hide file tree
Showing 4 changed files with 51 additions and 2 deletions.
7 changes: 7 additions & 0 deletions aip_xx1_description/config/sensors_calibration.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,11 @@
base_link:
ars408_front_center:
x: 3.8
y: 0.0
z: 0.5
roll: 0.0
pitch: 0.0
yaw: 0.0
sensor_kit_base_link:
x: 0.9
y: 0.0
Expand Down
31 changes: 31 additions & 0 deletions aip_xx1_description/urdf/radar.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="radar_macro" params="name parent x y z roll pitch yaw">
<xacro:property name="mass" value="0.01" />

<joint name="${name}_base_mount_joint" type="fixed">
<origin rpy="${roll} ${pitch} ${yaw}" xyz="${x} ${y} ${z}"/>
<parent link="${parent}"/>
<child link="${name}"/>
</joint>

<link name="${name}">
<visual>
<geometry>
<box size="0.03 0.1 0.1"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="${mass}"/>
<inertia ixx="${(0.03*0.03+0.03*0.03)*mass/12.0}" ixy="0.0" ixz="0.0"
iyy="${(0.1*0.1+0.1*0.1)*mass/12.0}" iyz="0.0"
izz="${(0.1*0.1+0.1*0.1)*mass/12.0}"/>
</inertial>
</link>
</xacro:macro>
</robot>
13 changes: 13 additions & 0 deletions aip_xx1_description/urdf/sensors.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -56,4 +56,17 @@
yaw="${calibration['base_link']['livox_front_right_base_link']['yaw']}"
/>

<!-- radar -->
<xacro:include filename="$(find aip_xx1_description)/urdf/radar.xacro"/>
<xacro:radar_macro
name="ars408_front_center"
parent="base_link"
x="${calibration['base_link']['ars408_front_center']['x']}"
y="${calibration['base_link']['ars408_front_center']['y']}"
z="${calibration['base_link']['ars408_front_center']['z']}"
roll="${calibration['base_link']['ars408_front_center']['roll']}"
pitch="${calibration['base_link']['ars408_front_center']['pitch']}"
yaw="${calibration['base_link']['ars408_front_center']['yaw']}"
/>

</robot>
2 changes: 0 additions & 2 deletions aip_xx1_launch/launch/radar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@
<push-ros-namespace namespace="front_center"/>

<!-- tf launch (temporary) -->
<node pkg="tf2_ros" exec="static_transform_publisher" name="base_link_to_ars408" output="screen" args="3.8 0.0 0.0 0.0 0.0 0.0 base_link ars408_front_center" />

<include file="$(find-pkg-share common_sensor_launch)/launch/ars408.launch.xml">
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="interface" value="$(var radar_can_device)" />
Expand Down

0 comments on commit 7c118dc

Please sign in to comment.