-
Notifications
You must be signed in to change notification settings - Fork 22
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
2f04d13
commit 7cabdc6
Showing
6 changed files
with
394 additions
and
0 deletions.
There are no files selected for viewing
Binary file not shown.
Binary file not shown.
Binary file not shown.
84 changes: 84 additions & 0 deletions
84
clearpath_sensors_description/urdf/axis_dome_fixed.urdf.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,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://axis_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
146
clearpath_sensors_description/urdf/axis_dome_ptz.urdf.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,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://axis_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> |
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,164 @@ | ||
<?xml version="1.0" ?> | ||
<robot xmlns:xacro="http://wiki.ros.org/xacro"> | ||
<xacro:macro name="axis_q62" params="prefix parent topic *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> | ||
</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> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://clearpth_sensors_description/meshes/axis_q62_base.stl" scale="0.001 0.001 0.001" /> | ||
</geometry> | ||
<material name="axis_grey"> | ||
<color rgba="0.7 0.7 0.7 1.0" /> | ||
</material> | ||
<origin xyz="-0.1 -0.17 0" rpy="0 0 0" /> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<cylinder radius="0.085" length="0.22" /> | ||
</geometry> | ||
<origin xyz="0 0 0.11" rpy="0 0 0" /> | ||
</collision> | ||
</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 0" rpy="0 0 0" /> | ||
</joint> | ||
<gazebo reference="${prefix}_body_link"> | ||
<material>Gazebo/Grey</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> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://clearpth_sensors_description/meshes/axis_q62_top.stl" scale="0.001 0.001 0.001" /> | ||
</geometry> | ||
<material name="axis_grey"> | ||
<color rgba="0.7 0.7 0.7 1.0" /> | ||
</material> | ||
<origin xyz="-0.1 -0.165 -0.215" rpy="0 0 0" /> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<cylinder radius="0.1" length="0.33" /> | ||
</geometry> | ||
<origin xyz="0 0 0" rpy="1.5707963267948966 0 0" /> | ||
</collision> | ||
</link> | ||
<joint name="${prefix}_tilt_joint" type="revolute"> | ||
<limit lower="-1.5707" 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.215" rpy="0 0 0" /> | ||
</joint> | ||
<gazebo reference="${prefix}_head_link"> | ||
<material>Gazebo/Grey</material> | ||
</gazebo> | ||
|
||
<!-- | ||
Add the shades & gazebo reference frame | ||
--> | ||
<link name="${prefix}_camera_link"> | ||
<visual> | ||
<geometry> | ||
<box size="0.03 0.09 0.01" /> | ||
</geometry> | ||
<origin xyz="-0.01 0 0.05" rpy="0 0 0" /> | ||
<material name="black" /> | ||
</visual> | ||
<visual> | ||
<geometry> | ||
<box size="0.03 0.09 0.01" /> | ||
</geometry> | ||
<origin xyz="-0.01 0.20 0.05" rpy="0 0 0" /> | ||
<material name="black" /> | ||
</visual> | ||
</link> | ||
<joint name="${prefix}_camera_joint" type="fixed"> | ||
<parent link="${prefix}_head_link" /> | ||
<child link="${prefix}_camera_link" /> | ||
<origin xyz="0.1 -0.107 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> |