-
Notifications
You must be signed in to change notification settings - Fork 98
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Absolem: Added sensor configs 6, 7 and 8.
- Loading branch information
Showing
43 changed files
with
13,888 additions
and
46 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
96 changes: 96 additions & 0 deletions
96
submitted_models/ctu_cras_norlab_absolem_sensor_config_1/meshes/basler_ace2_pro.dae
Large diffs are not rendered by default.
Oops, something went wrong.
155 changes: 155 additions & 0 deletions
155
submitted_models/ctu_cras_norlab_absolem_sensor_config_1/meshes/evetar_lens.dae
Large diffs are not rendered by default.
Oops, something went wrong.
111 changes: 111 additions & 0 deletions
111
submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/basler_cameras.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,111 @@ | ||
<?xml version="1.0"?> | ||
<root xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
<!-- Mass properties from datasheet --> | ||
<xacro:property name="basler_ace_mass" value="0.09" scope="global" /> | ||
<xacro:property name="basler_ace2_pro_mass" value="0.105" scope="global" /> | ||
<xacro:property name="fisheye_lens_mass" value="0.05" scope="global" /> | ||
<xacro:property name="omnicam_lens_mass" value="0.127" scope="global" /> | ||
<xacro:property name="c_mount_flange_distance" value="0.017526" scope="global" /> | ||
<xacro:property name="c_mount_radius" value="${0.025/2}" scope="global" /> | ||
|
||
<xacro:macro name="basler_ace_base" params="name hfov_deg frame_rate resolution_x resolution_y fisheye:=0 camera_length origin_to_camera_front_dist camera_mass camera_mesh lens_length lens_back_focal_distance lens_entrance_pupil_position lens_mass lens_mesh near_clip:=-1 simulate:=1 visualize:=0"> | ||
<xacro:property name="camera_width" value="0.029"/> | ||
<xacro:property name="camera_height" value="0.029"/> | ||
|
||
<xacro:property name="sensor_chip_pos" value="${origin_to_camera_front_dist - c_mount_flange_distance}" /> | ||
<xacro:property name="lens_back_pos" value="${sensor_chip_pos + lens_back_focal_distance}" /> | ||
|
||
<link name="$(arg prefix)${name}"> | ||
<visual> | ||
<origin xyz="0 0 ${camera_height/2}" rpy="0 0 0" /> | ||
<geometry> | ||
<!-- The origin of the mesh is center above tripod screw --> | ||
<mesh filename="${camera_mesh}"/> | ||
</geometry> | ||
</visual> | ||
<visual> | ||
<!-- The origin of the mesh is at the back of the lens --> | ||
<origin xyz="${lens_back_pos} 0 ${camera_height/2}" rpy="0 0 0" /> | ||
<geometry> | ||
<mesh filename="${lens_mesh}"/> | ||
</geometry> | ||
</visual> | ||
<collision name="${name}_collision"> | ||
<origin rpy="0 0 0" xyz="${origin_to_camera_front_dist - camera_length/2} 0 ${camera_height/2}"/> | ||
<geometry> | ||
<box size="${camera_length} ${camera_width} ${camera_height}" /> | ||
</geometry> | ||
</collision> | ||
<collision name="${name}_lens_collision"> | ||
<origin rpy="0 ${pi/2} 0" xyz="${lens_back_pos + lens_length/2} 0 ${camera_height/2}"/> | ||
<geometry> | ||
<cylinder length="${lens_length}" radius="${c_mount_radius}" /> | ||
</geometry> | ||
</collision> | ||
<xacro:box_inertial mass="${camera_mass + lens_mass}" | ||
width="${camera_width}" height="${camera_height}" depth="${camera_length + lens_length - (c_mount_flange_distance - lens_back_focal_distance)}" | ||
xyz="${origin_to_camera_front_dist + (lens_length - (c_mount_flange_distance - lens_back_focal_distance))/2 - camera_length/2} 0 ${camera_height/2}" /> | ||
</link> | ||
<xacro:if value="${simulate}"> | ||
<gazebo reference="$(arg prefix)${name}"> | ||
<!-- Workaround for https://github.com/ignitionrobotics/ign-sensors/issues/24 --> | ||
<xacro:if value="${fisheye == 0 or '$(arg rendering_target)' == 'ign'}"> | ||
<xacro:property name="cam_type" value="camera"/> | ||
</xacro:if> | ||
<xacro:unless value="${fisheye == 0 or '$(arg rendering_target)' == 'ign'}"> | ||
<xacro:property name="cam_type" value="wideanglecamera"/> | ||
</xacro:unless> | ||
<sensor name="${name}" type="${cam_type}"> | ||
<!-- I think the simulated sensor should be placed in the middle of the entrance pupil. --> | ||
<xacro:property name="virtual_lens_origin" value="${lens_back_pos + lens_length - lens_entrance_pupil_position}" /> | ||
<pose>${virtual_lens_origin} 0 ${camera_height/2} 0 0 0</pose> | ||
<update_rate>${frame_rate}</update_rate> | ||
<visualize>${visualize}</visualize> | ||
<camera> | ||
<horizontal_fov>${radians(hfov_deg)}</horizontal_fov> | ||
<image> | ||
<width>${resolution_x}</width> | ||
<height>${resolution_y}</height> | ||
<format>R8G8B8</format> | ||
</image> | ||
<clip> | ||
<xacro:property name="clip" value="${lens_entrance_pupil_position * 1.1 if near_clip == -1 else near_clip}" /> | ||
<near>${clip}</near> | ||
<far>300</far> | ||
</clip> | ||
<noise> | ||
<type>gaussian</type> | ||
<mean>0.0</mean> | ||
<stddev>0.007</stddev> | ||
</noise> | ||
<xacro:if value="${fisheye and '$(arg rendering_target)' == 'gz'}"> | ||
<lens> | ||
<type>stereographic</type> | ||
<scale_to_hfov>true</scale_to_hfov> | ||
<cutoff_angle>${pi}</cutoff_angle> | ||
<env_texture_size>1024</env_texture_size> | ||
</lens> | ||
</xacro:if> | ||
</camera> | ||
</sensor> | ||
</gazebo> | ||
</xacro:if> | ||
</xacro:macro> | ||
|
||
<xacro:macro name="basler_ace2_pro_link" params="name hfov_deg fisheye:=0 lens_length lens_back_focal_distance lens_entrance_pupil_position lens_mass lens_mesh near_clip:=-1 simulate:=1 visualize:=0"> | ||
<xacro:basler_ace_base name="${name}" hfov_deg="${hfov_deg}" frame_rate="9" resolution_x="1920" resolution_y="1200" | ||
fisheye="${fisheye}" simulate="${simulate}" visualize="${visualize}" | ||
camera_length="0.0555" origin_to_camera_front_dist="0.0524" camera_mass="${basler_ace2_pro_mass}" | ||
camera_mesh="package://ctu_cras_norlab_absolem_sensor_config_1/meshes/basler_ace2_pro.dae" | ||
lens_length="${lens_length}" lens_back_focal_distance="${lens_back_focal_distance}" | ||
lens_entrance_pupil_position="${lens_entrance_pupil_position}" lens_mass="${lens_mass}" lens_mesh="${lens_mesh}" | ||
near_clip="${near_clip}" | ||
/> | ||
</xacro:macro> | ||
|
||
<xacro:macro name="basler_ace_omnicam" params="name simulate:=1 visualize:=0"> | ||
<xacro:basler_ace2_pro_link name="${name}" hfov_deg="86.5" simulate="${simulate}" visualize="${visualize}" | ||
lens_back_focal_distance="0.00809" lens_entrance_pupil_position="0.01066" lens_length="0.03974" lens_mass="${omnicam_lens_mass}" | ||
lens_mesh="package://ctu_cras_norlab_absolem_sensor_config_1/meshes/evetar_lens.dae" /> | ||
</xacro:macro> | ||
</root> |
Oops, something went wrong.