update: include oak-d-lite

This commit is contained in:
Björn Ellensohn 2023-09-21 11:11:04 +02:00
parent e1e8922bb4
commit 5ef00ced5c
6 changed files with 226 additions and 0 deletions

View File

@ -0,0 +1,78 @@
<?xml version="1.0"?>
<robot name="base"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="base" params="camera_name camera_model parent base_frame
cam_pos_x cam_pos_y cam_pos_z
cam_roll cam_pitch cam_yaw has_imu r:=0.8 g:=0.8 b:=0.8 a:=0.8 ">
<!-- base_link of the sensor-->
<link name="${base_frame}"/>
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:property name="model" value="${camera_model}" />
<joint name="${camera_name}_center_joint" type="fixed">
<parent link="${parent}"/>
<child link="${base_frame}"/>
<origin xyz="${cam_pos_x} ${cam_pos_y} ${cam_pos_z}" rpy="${cam_roll} ${cam_pitch} ${cam_yaw}" />
</joint>
<!-- device Center -->
<link name="${camera_name}_model_origin">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://depthai_descriptions/urdf/models/${model}.stl" />
</geometry>
<material name="mat">
<color rgba="${r} ${g} ${b} ${a}"/>
</material>
</visual>
</link>
<joint name="${camera_name}_model_origin_joint" type="fixed">
<parent link="${base_frame}"/>
<child link="${camera_name}_model_origin"/>
<origin xyz="0 0 0" rpy="1.5708 0 1.5708" />
</joint>
<!-- IMU -->
<xacro:if value="${model == 'OAK-D'}">
<xacro:property name="imu_offset_x" value="0.0" />
<xacro:property name="imu_offset_y" value="-0.015" />
<xacro:property name="imu_offset_z" value="-0.013662" />
<xacro:property name="imu_r" value="0.0" />
<xacro:property name="imu_p" value="${M_PI/2.0}" />
<xacro:property name="imu_y" value="0.0" />
</xacro:if>
<xacro:if value="${model == 'OAK-D-PRO'}">
<xacro:property name="imu_offset_x" value="-0.008" />
<xacro:property name="imu_offset_y" value="-0.037945" />
<xacro:property name="imu_offset_z" value="-0.00079" />
<xacro:property name="imu_r" value="${M_PI}" />
<xacro:property name="imu_p" value="${M_PI/2.0}" />
<xacro:property name="imu_y" value="0.0" />
</xacro:if>
<xacro:if value="${model == 'OAK-D-POE'}">
<xacro:property name="imu_offset_x" value="-0.008" />
<xacro:property name="imu_offset_y" value="-0.04" />
<xacro:property name="imu_offset_z" value="-0.020265" />
<xacro:property name="imu_r" value="${M_PI}" />
<xacro:property name="imu_p" value="${M_PI/2.0}" />
<xacro:property name="imu_y" value="0.0" />
</xacro:if>
<xacro:if value="${has_imu}">
<link name="${camera_name}_imu_frame" />
<joint name="${camera_name}_imu_joint" type="fixed">
<parent link="${base_frame}"/>
<child link="${camera_name}_imu_frame"/>
<origin xyz="${imu_offset_x} ${imu_offset_y} ${imu_offset_z}" rpy="${imu_r} ${imu_p} ${imu_y}" />
</joint>
</xacro:if>
</xacro:macro>
</robot>

View File

@ -0,0 +1,76 @@
<?xml version="1.0"?>
<robot name="depthai_camera"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="depthai_camera" params="camera_name camera_model parent base_frame
cam_pos_x cam_pos_y cam_pos_z
cam_roll cam_pitch cam_yaw r:=0.8 g:=0.8 b:=0.8 a:=0.8 ">
<xacro:include filename="$(find cps_rmp220_support)/description/include/base_macro.urdf.xacro"/>
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:property name="model" value="${camera_model}" />
<xacro:property name="has_imu" value="false" />
<xacro:property name="baseline" value="0.075" />
<xacro:if value="${model == 'OAK-D'}">
<xacro:property name="has_imu" value="true" />
</xacro:if>
<xacro:base camera_name = "$(arg camera_name)" parent = "$(arg parent_frame)" camera_model = "$(arg camera_model)" base_frame = "$(arg base_frame)" cam_pos_x = "$(arg cam_pos_x)" cam_pos_y = "$(arg cam_pos_y)" cam_pos_z = "$(arg cam_pos_z)" cam_roll = "$(arg cam_roll)" cam_pitch = "$(arg cam_pitch)" cam_yaw = "$(arg cam_yaw)" has_imu="${has_imu}"/>
<!-- RGB Camera -->
<link name="${camera_name}_rgb_camera_frame" />
<joint name="${camera_name}_rgb_camera_joint" type="fixed">
<parent link="${base_frame}"/>
<child link="${camera_name}_rgb_camera_frame"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="${camera_name}_rgb_camera_optical_frame"/>
<joint name="${camera_name}_rgb_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0.0 -${M_PI/2}"/>
<parent link="${camera_name}_rgb_camera_frame"/>
<child link="${camera_name}_rgb_camera_optical_frame"/>
</joint>
<!-- Left Camera -->
<link name="${camera_name}_left_camera_frame" />
<joint name="${camera_name}_left_camera_joint" type="fixed">
<parent link="${base_frame}"/>
<child link="${camera_name}_left_camera_frame"/>
<origin xyz="0 ${baseline/2} 0" rpy="0 0 0" />
</joint>
<link name="${camera_name}_left_camera_optical_frame"/>
<joint name="${camera_name}_left_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0.0 -${M_PI/2}"/>
<parent link="${camera_name}_left_camera_frame"/>
<child link="${camera_name}_left_camera_optical_frame"/>
</joint>
<!-- right Camera -->
<link name="${camera_name}_right_camera_frame" />
<joint name="${camera_name}_right_camera_joint" type="fixed">
<parent link="${base_frame}"/>
<child link="${camera_name}_right_camera_frame"/>
<origin xyz="0 -${baseline/2} 0" rpy="0 0 0" />
</joint>
<link name="${camera_name}_right_camera_optical_frame"/>
<joint name="${camera_name}_right_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0.0 -${M_PI/2}"/>
<parent link="${camera_name}_right_camera_frame"/>
<child link="${camera_name}_right_camera_optical_frame"/>
</joint>
</xacro:macro>
</robot>

Binary file not shown.

View File

@ -0,0 +1,46 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:arg name="camera_name" default="oak" />
<xacro:arg name="camera_model" default="OAK-D" />
<xacro:arg name="base_frame" default="oak-d_frame" />
<xacro:arg name="parent_frame" default="oak-d-base-frame" />
<xacro:arg name="cam_pos_x" default="0.0" />
<xacro:arg name="cam_pos_y" default="0.0" />
<xacro:arg name="cam_pos_z" default="0.0" />
<xacro:arg name="cam_roll" default="0.0" />
<xacro:arg name="cam_pitch" default="0.0" />
<xacro:arg name="cam_yaw" default="0.0" />
<xacro:include filename="$(find depthai_descriptions)/urdf/include/depthai_macro.urdf.xacro"/>
<link name="$(arg parent_frame)"/>
<xacro:depthai_camera camera_name = "$(arg camera_name)" parent = "$(arg parent_frame)" camera_model = "$(arg camera_model)" base_frame = "$(arg base_frame)" cam_pos_x = "$(arg cam_pos_x)" cam_pos_y = "$(arg cam_pos_y)" cam_pos_z = "$(arg cam_pos_z)" cam_roll = "$(arg cam_roll)" cam_pitch = "$(arg cam_pitch)" cam_yaw = "$(arg cam_yaw)"/>
<xacro:arg name="camera_name" default="oak" />
<xacro:arg name="camera_model" default="OAK-D-LITE" />
<xacro:arg name="base_frame" default="oak-d_frame" />
<xacro:arg name="parent_frame" default="oak-d-base-frame" />
<xacro:arg name="cam_pos_x" default="0.0" />
<xacro:arg name="cam_pos_y" default="0.0" />
<xacro:arg name="cam_pos_z" default="0.0" />
<xacro:arg name="cam_roll" default="0.0" />
<xacro:arg name="cam_pitch" default="0.0" />
<xacro:arg name="cam_yaw" default="0.0" />
<xacro:arg name="has_imu" default="false" />
<xacro:include filename="$(find depthai_descriptions)/urdf/include/base_macro.urdf.xacro"/>
<link name="$(arg parent_frame)"/>
<xacro:base camera_name = "$(arg camera_name)" parent = "$(arg parent_frame)" camera_model = "$(arg camera_model)" base_frame = "$(arg base_frame)" cam_pos_x = "$(arg cam_pos_x)" cam_pos_y = "$(arg cam_pos_y)" cam_pos_z = "$(arg cam_pos_z)" cam_roll = "$(arg cam_roll)" cam_pitch = "$(arg cam_pitch)" cam_yaw = "$(arg cam_yaw)" has_imu="$(arg has_imu)"/>
<joint name="oak-d-base-joint" type="fixed">
<parent link="chassis"/>
<child link="oak-d-base-frame"/>
<origin xyz="0 0 ${chassis_height/2 - 0.010}" rpy="0 0 0"/>
</joint>
<link name="oak-d-base-frame">
</link>
</robot>

View File

@ -19,5 +19,8 @@
<xacro:include filename="face.xacro" />
<xacro:include filename="imu.xacro" />
<!-- New xacro file defining oak-d-lite depth camera -->
<xacro:include filename="oak-d-lite.xacro"/>
</robot>

23
launch/oakd.launch.py Normal file
View File

@ -0,0 +1,23 @@
import os
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='v4l2_camera',
executable='v4l2_camera_node',
output='screen',
namespace='camera',
parameters=[{
'image_size': [640,480],
'time_per_frame': [1, 6],
'camera_frame_id': 'camera_link_optical'
}]
)
])