Skip to content
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
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ further information.

## Remarks
* For using this package, you need to have the [Ensenso SDK](https://www.ensenso.com/support/sdk-download) installed.
* Ensenso B-Series cameras require at least version 2.1.3
* Ensenso C-Series cameras require at least version 2.1.1
* Ensenso S- and XR-Series cameras require at least version 1.7.0.
* Version 1.7.0 and newer requires at least Ensenso SDK 3.0.
Expand Down
52 changes: 52 additions & 0 deletions ensenso_description/ensenso.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -246,4 +246,56 @@
<link name="${name}_left_lens_frame"/>
</xacro:macro>

<xacro:macro name="ensenso_CxL_Series" params="name margin:=0.03">
<link name="${name}">
<visual>
<origin rpy="0 0 ${pi}" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ensenso_description/stl_meshes/Cx-L.stl"/>
</geometry>
<material name="Ensenso/DarkGrey"/>
</visual>
<collision>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 ${0.10/2}"/>
<geometry>
<box size="${margin+0.910} ${margin+0.06} ${margin+0.10+0.02}"/>
</geometry>
</collision>
</link>

<!-- Left lens -->
<joint name="${name}_left_lens_joint" type="fixed">
<parent link="${name}"/>
<child link="${name}_left_lens_frame"/>
<origin xyz="${-0.850/2} 0 0.032" rpy="0 0 0"/>
</joint>
<link name="${name}_left_lens_frame"/>
</xacro:macro>

<xacro:macro name="ensenso_Bx_Series" params="name margin:=0.03">
<link name="${name}">
<visual>
<origin rpy="0 0 ${pi}" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ensenso_description/stl_meshes/Bx.stl"/>
</geometry>
<material name="Ensenso/DarkGrey"/>
</visual>
<collision>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 ${(0.104+0.01)/2}"/>
<geometry>
<box size="${margin+0.120} ${margin+0.056} ${margin+0.104+0.02}"/>
</geometry>
</collision>
</link>

<!-- Left lens -->
<joint name="${name}_left_lens_joint" type="fixed">
<parent link="${name}"/>
<child link="${name}_left_lens_frame"/>
<origin xyz="${-0.075/2} 0 0.090" rpy="0 0 0"/>
</joint>
<link name="${name}_left_lens_frame"/>
</xacro:macro>

</robot>
29 changes: 29 additions & 0 deletions ensenso_description/ensenso_Bx_Series.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0"?>
<robot name="ensenso_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find ensenso_description)/ensenso.xacro" />

<!-- Parameters -->
<!-- Name of the camera -->
<xacro:arg name="camera" default="B57" />
<xacro:property name="camera_name" value="$(arg camera)" />

<!-- Enlarges the bounding box in all directions -->
<xacro:arg name="margin" default="0.03" />
<xacro:property name="margin" value="$(arg margin)" />

<!-- tf frame that references to the cameras mounting frame -->
<xacro:arg name="corresponding_frame_name" default="base_link" />
<xacro:property name="corresponding_frame_name" value="$(arg corresponding_frame_name)" />

<xacro:ensenso_Bx_Series name="${camera_name}" margin="${margin}"/>
<joint name="${corresponding_frame_name}_to_${camera_name}" type="fixed">
<parent link="${corresponding_frame_name}" />
<child link="${camera_name}" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${corresponding_frame_name}" />
</robot>
<!-- Example usage with:
roslaunch urdf_tutorial display.launch model:=`rospack find ensenso_description`/ensenso_Bx_Series.xacro gui:=true
-->
29 changes: 29 additions & 0 deletions ensenso_description/ensenso_CxL_Series.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0"?>
<robot name="ensenso_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find ensenso_description)/ensenso.xacro" />

<!-- Parameters -->
<!-- Name of the camera -->
<xacro:arg name="camera" default="C57L" />
<xacro:property name="camera_name" value="$(arg camera)" />

<!-- Enlarges the bounding box in all directions -->
<xacro:arg name="margin" default="0.03" />
<xacro:property name="margin" value="$(arg margin)" />

<!-- tf frame that references to the cameras mounting frame -->
<xacro:arg name="corresponding_frame_name" default="base_link" />
<xacro:property name="corresponding_frame_name" value="$(arg corresponding_frame_name)" />

<xacro:ensenso_CxL_Series name="${camera_name}" margin="${margin}"/>
<joint name="${corresponding_frame_name}_to_${camera_name}" type="fixed">
<parent link="${corresponding_frame_name}" />
<child link="${camera_name}" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${corresponding_frame_name}" />
</robot>
<!-- Example usage with:
roslaunch urdf_tutorial display.launch model:=`rospack find ensenso_description`/ensenso_CxL_Series.xacro gui:=true
-->
3 changes: 3 additions & 0 deletions ensenso_description/stl_meshes/Bx.stl
Git LFS file not shown
3 changes: 3 additions & 0 deletions ensenso_description/stl_meshes/Cx-L.stl
Git LFS file not shown
Loading