Skip to content

Commit

Permalink
Revert "Now that axis_camera is released via OSRF, depend on the offi…
Browse files Browse the repository at this point in the history
…cial package, remove duplicate meshes, URDFs"

This reverts commit 4ee2313.
  • Loading branch information
civerachb-cpr committed Dec 3, 2024
1 parent 4b79120 commit 96b02be
Show file tree
Hide file tree
Showing 8 changed files with 401 additions and 4 deletions.
Binary file not shown.
Binary file not shown.
Binary file not shown.
1 change: 0 additions & 1 deletion clearpath_sensors_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>axis_description</exec_depend>
<exec_depend>microstrain_inertial_description</exec_depend>
<exec_depend>realsense2_description</exec_depend>
<exec_depend>velodyne_description</exec_depend>
Expand Down
84 changes: 84 additions & 0 deletions clearpath_sensors_description/urdf/axis/axis_dome_fixed.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="axis_dome_fixed" params="prefix parent topic stand_height:=0.062 *origin">
<link name="${prefix}_base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_dome.stl" scale="1 1 1" />
</geometry>
<material name="axis_white">
<color rgba="0.8 0.8 0.8 1.0" />
</material>
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<collision>
<!-- Cylinder for the main body of the camera -->
<geometry>
<cylinder radius="0.09" length="0.09" />
</geometry>
<origin xyz="0 0 ${stand_height + 0.09/2}" rpy="0 0 0" />
</collision>
<collision>
<!-- Sphere collider for the dome itself -->
<geometry>
<sphere radius="0.067" />
</geometry>
<origin xyz="0 0 ${stand_height + 0.09}" />
</collision>
<collision>
<!-- Box collider for the metal stand the camera sits on -->
<geometry>
<box size="0.04 0.08 ${stand_height}" />
</geometry>
<origin xyz="0 0 ${stand_height/2}" rpy="0 0 0" />
</collision>
</link>
<joint name="${prefix}_base_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_base_link" />
</joint>

<link name="${prefix}_camera_link" />
<joint name="${prefix}_camera_joint" type="fixed">
<parent link="${prefix}_base_link" />
<child link="${prefix}_camera_link" />
<origin xyz="0.047 0 ${stand_height + 0.09 + 0.047}" rpy="0 0.7854 0" />
</joint>

<gazebo reference="${prefix}_camera_link">
<material>Gazebo/Black</material>
<sensor type="camera" name="${prefix}_dome_camera">
<update_rate>15</update_rate>
<camera>
<horizontal_fov>6.28</horizontal_fov>
<vertical_fov>1.57</vertical_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>500.0</far>
</clip>
</camera>
<plugin name="${prefix}_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${prefix}_camera</cameraName>
<imageTopicName>${topic}</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${prefix}_camera_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
146 changes: 146 additions & 0 deletions clearpath_sensors_description/urdf/axis/axis_dome_ptz.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,146 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="axis_dome_ptz" params="prefix parent topic stand_height:=0.062 *origin">
<link name="${prefix}_base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_dome.stl" scale="1 1 1" />
</geometry>
<material name="axis_white">
<color rgba="0.8 0.8 0.8 1.0" />
</material>
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
<collision>
<!-- Cylinder for the main body of the camera -->
<geometry>
<cylinder radius="0.09" length="0.09" />
</geometry>
<origin xyz="0 0 ${stand_height + 0.09/2}" rpy="0 0 0" />
</collision>
<collision>
<!-- Sphere collider for the dome itself -->
<geometry>
<sphere radius="0.067" />
</geometry>
<origin xyz="0 0 ${stand_height + 0.09}" />
</collision>
<collision>
<!-- Box collider for the metal stand the camera sits on -->
<geometry>
<box size="0.04 0.08 ${stand_height}" />
</geometry>
<origin xyz="0 0 ${stand_height/2}" rpy="0 0 0" />
</collision>
</link>
<joint name="${prefix}_base_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}_base_link" />
</joint>

<link name="${prefix}_body_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<joint name="${prefix}_pan_joint" type="continuous">
<axis xyz="0 0 -1" />
<parent link="${prefix}_base_link" />
<child link="${prefix}_body_link" />
<origin xyz="0 0 ${stand_height}" rpy="0 0 0" />
</joint>
<gazebo reference="${prefix}_body_link">
<material>Gazebo/LightGrey</material>
</gazebo>

<link name="${prefix}_head_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<joint name="${prefix}_tilt_joint" type="revolute">
<limit lower="0" upper="1.5707" effort="1" velocity="3.14159" />
<axis xyz="0 -1 0" />
<parent link="${prefix}_body_link" />
<child link="${prefix}_head_link" />
<origin xyz="0 0 0.09" rpy="0 0 0" />
</joint>

<!--
Add the gazebo reference frame
-->
<link name="${prefix}_camera_link" />
<joint name="${prefix}_camera_joint" type="fixed">
<parent link="${prefix}_head_link" />
<child link="${prefix}_camera_link" />
<origin xyz="0.067 0 0" rpy="0 0 0" />
</joint>

<!--
Simulation support: camera plugin & transmissions to allow control over the joints
-->
<transmission name="${prefix}_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_pan_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_pan_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}_tilt_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_tilt_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_tilt_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="${prefix}_camera_link">
<material>Gazebo/Black</material>
<sensor type="camera" name="${prefix}_ptz_camera">
<update_rate>15</update_rate>
<camera>
<horizontal_fov>1.5184351666666667</horizontal_fov>
<vertical_fov>1.0122901111111111</vertical_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>500.0</far>
</clip>
</camera>
<plugin name="${prefix}_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${prefix}_camera</cameraName>
<imageTopicName>${topic}</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${prefix}_camera_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
Loading

0 comments on commit 96b02be

Please sign in to comment.