Skip to content

Commit facdf3f

Browse files
committed
Add axis_p5676 camera
1 parent e203591 commit facdf3f

File tree

3 files changed

+210
-0
lines changed

3 files changed

+210
-0
lines changed

meshes/axis_p5676.stl

747 KB
Binary file not shown.

urdf/all_sensors.urdf.xacro

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,9 @@
1919
<!-- Axis m5525 -->
2020
<xacro:include filename="$(find robotnik_sensors)/urdf/axis_m5525.urdf.xacro" />
2121

22+
<!-- Axis p5676 -->
23+
<xacro:include filename="$(find robotnik_sensors)/urdf/axis_p5676.urdf.xacro" />
24+
2225
<!-- Axis q8641 -->
2326
<xacro:include filename="$(find robotnik_sensors)/urdf/axis_q8641.urdf.xacro" />
2427

urdf/axis_p5676.urdf.xacro

Lines changed: 207 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,207 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="sensor_axis_p5676">
3+
<xacro:property name="ptz_joint_effort_limit" value="1.0"/>
4+
<xacro:property name="ptz_joint_velocity_limit" value="1.0"/>
5+
<xacro:property name="ptz_joint_friction" value="0.1"/>
6+
<xacro:property name="ptz_joint_damping" value="0.1"/>
7+
<xacro:property name="ptz_mechanical_reduction" value="1.0"/>
8+
<xacro:property name="PI" value="3.14159265359"/>
9+
10+
<xacro:macro name="sensor_axis_p5676" params="prefix parent *origin far:=^|8.0 near:=^|0.05 prefix_topic:=^ptz_camera include_inertial:=^|true">
11+
<joint name="${prefix}_joint" type="fixed">
12+
<axis xyz="0 0 1"/>
13+
<xacro:insert_block name="origin"/>
14+
<parent link="${parent}"/>
15+
<child link="${prefix}_base_link"/>
16+
</joint>
17+
<link name="${prefix}_base_link">
18+
<xacro:if value="${include_inertial}">
19+
<inertial>
20+
<origin xyz="0.066 0 0" rpy="0 0 0"/>
21+
<mass value="2.5"/>
22+
<xacro:solid_cuboid_inertia m="2.5" w="0.205" h="0.242" d="0.205" />
23+
</inertial>
24+
</xacro:if>
25+
<visual>
26+
<origin xyz="0 0 0" rpy="0 0 0"/>
27+
<!-- to center the axis model -->
28+
<material name="axis_color">
29+
<color rgba="0.1 0.1 0.1 1"/>
30+
</material>
31+
<geometry>
32+
<mesh filename="package://robotnik_sensors/meshes/axis_p5676.stl" scale="1.0 1.0 1.0"/>
33+
</geometry>
34+
</visual>
35+
<collision>
36+
<origin xyz="0.0 0.0 0" rpy="0 0 0"/>
37+
<geometry>
38+
<mesh filename="package://robotnik_sensors/meshes/axis_p5676.stl" scale="1.0 1.0 1.0"/>
39+
</geometry>
40+
</collision>
41+
</link>
42+
43+
<joint name="${prefix}_pan_joint" type="revolute">
44+
<axis xyz="0 0 1"/>
45+
<origin xyz="0 0.0 0.065" rpy="0 0 0"/>
46+
<!-- check the displacement -->
47+
<parent link="${prefix}_base_link"/>
48+
<child link="${prefix}_pan_link"/>
49+
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-3.1416" upper="3.1416"/>
50+
<joint_properties damping="${ptz_joint_damping}" friction="{ptz_joint_friction}"/>
51+
</joint>
52+
<link name="${prefix}_pan_link">
53+
<xacro:if value="${include_inertial}">
54+
<inertial>
55+
<mass value="0.1"/>
56+
<origin xyz="0 0 0" rpy="0 0 0"/>
57+
<xacro:solid_cuboid_inertia m="0.1" w="0.1" h="0.11" d="0.11" />
58+
</inertial>
59+
</xacro:if>
60+
</link>
61+
<transmission name="${prefix}_pan_trans">
62+
<type>transmission_interface/SimpleTransmission</type>
63+
<joint name="${prefix}_pan_joint">
64+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
65+
</joint>
66+
<actuator name="${prefix}pan_motor">
67+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
68+
<mechanicalReduction>${ptz_mechanical_reduction}</mechanicalReduction>
69+
</actuator>
70+
</transmission>
71+
<joint name="${prefix}_tilt_joint" type="revolute">
72+
<axis xyz="0 0 1"/>
73+
<origin xyz="0.0 0.0 0.0" rpy="${PI/2} 0 0"/>
74+
<parent link="${prefix}_pan_link"/>
75+
<child link="${prefix}_tilt_link"/>
76+
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-1.5708" upper="1.5708"/>
77+
<joint_properties damping="${ptz_joint_damping}" friction="{ptz_joint_friction}"/>
78+
</joint>
79+
<link name="${prefix}_tilt_link">
80+
<xacro:if value="${include_inertial}">
81+
<inertial>
82+
<mass value="0.1"/>
83+
<origin xyz="0 0 0" rpy="0 0 0"/>
84+
<xacro:solid_cuboid_inertia m="0.1" w="0.11" h="0.11" d="0.1" />
85+
</inertial>
86+
</xacro:if>
87+
</link>
88+
<transmission name="${prefix}_tilt_trans">
89+
<type>transmission_interface/SimpleTransmission</type>
90+
<joint name="${prefix}_tilt_joint">
91+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
92+
</joint>
93+
<actuator name="${prefix}tilt_motor">
94+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
95+
<mechanicalReduction>${ptz_mechanical_reduction}</mechanicalReduction>
96+
</actuator>
97+
</transmission>
98+
99+
100+
<joint name="${prefix}_zoom_joint" type="prismatic">
101+
<axis xyz="1 0 0"/>
102+
<origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0 0"/>
103+
<parent link="${prefix}_tilt_link"/>
104+
<child link="${prefix}_zoom_link"/>
105+
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-1.5708" upper="1.5708"/>
106+
<joint_properties damping="${ptz_joint_damping}" friction="{ptz_joint_friction}"/>
107+
</joint>
108+
<link name="${prefix}_zoom_link">
109+
<xacro:if value="${include_inertial}">
110+
<inertial>
111+
<mass value="0.1"/>
112+
<origin xyz="0 0 0" rpy="0 0 0"/>
113+
<xacro:solid_cuboid_inertia m="0.1" w="0.11" h="0.11" d="0.1" />
114+
</inertial>
115+
</xacro:if>
116+
</link>
117+
<transmission name="${prefix}_zoom_trans">
118+
<type>transmission_interface/SimpleTransmission</type>
119+
<joint name="${prefix}_zoom_joint">
120+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
121+
</joint>
122+
<actuator name="${prefix}zoom_motor">
123+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
124+
<mechanicalReduction>${ptz_mechanical_reduction}</mechanicalReduction>
125+
</actuator>
126+
</transmission>
127+
128+
129+
<joint name="${prefix}_frame_joint" type="fixed">
130+
<origin xyz="0 0 0" rpy="0 0 0"/>
131+
<parent link="${prefix}_tilt_link"/>
132+
<child link="${prefix}_frame_link"/>
133+
</joint>
134+
<link name="${prefix}_frame_link">
135+
<xacro:if value="${include_inertial}">
136+
<inertial>
137+
<mass value="0.1"/>
138+
<origin xyz="0 0 0"/>
139+
<xacro:solid_cuboid_inertia m="0.1" w="0.11" h="0.11" d="0.1" />
140+
</inertial>
141+
</xacro:if>
142+
</link>
143+
<!-- Optical frame -->
144+
<joint name="${prefix}_optical_joint" type="fixed">
145+
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}"/>
146+
<parent link="${prefix}_frame_link"/>
147+
<child link="${prefix}_optical_frame_link"/>
148+
</joint>
149+
<link name="${prefix}_optical_frame_link">
150+
<xacro:if value="${include_inertial}">
151+
<inertial>
152+
<mass value="0.1"/>
153+
<origin xyz="0 0 0"/>
154+
<xacro:solid_cuboid_inertia m="0.1" w="0.11" h="0.11" d="0.1" />
155+
</inertial>
156+
</xacro:if>
157+
</link>
158+
<gazebo reference="${prefix}_base_link">
159+
<material>Gazebo/DarkGrey</material>
160+
</gazebo>
161+
162+
<!-- Axis sensor for simulation -->
163+
<xacro:sensor_axis_p5676_gazebo/>
164+
165+
</xacro:macro>
166+
167+
168+
<xacro:macro name="sensor_axis_p5676_gazebo">
169+
170+
<gazebo reference="${prefix}_frame_link"> <!-- the image will be generated from this (${name}_frame) point of view, with the front being the X axis -->
171+
<sensor type="camera" name="${prefix}_sensor">
172+
<update_rate>30.0</update_rate>
173+
<camera name="${prefix_topic}">
174+
<horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
175+
<image>
176+
<format>R8G8B8</format>
177+
<width>640</width>
178+
<height>480</height>
179+
</image>
180+
<clip>
181+
<near>${near}</near>
182+
<far>${far}</far>
183+
</clip>
184+
</camera>
185+
<plugin name="${prefix}_controller" filename="libgazebo_ros_camera.so">
186+
<alwaysOn>true</alwaysOn>
187+
<updateRate>0.0</updateRate>
188+
<cameraName>${prefix_topic}</cameraName>
189+
<imageTopicName>image_raw</imageTopicName>
190+
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
191+
<frameName>${prefix}_optical_frame_link</frameName>
192+
<!-- this is just which name the Image msg will have, it does not affect the simulation.
193+
However must be set to the optical_frame, -->
194+
<hackBaseline>0.07</hackBaseline>
195+
<distortionK1>0.0</distortionK1>
196+
<distortionK2>0.0</distortionK2>
197+
<distortionK3>0.0</distortionK3>
198+
<distortionT1>0.0</distortionT1>
199+
<distortionT2>0.0</distortionT2>
200+
<ignoreTfPrefix>1</ignoreTfPrefix>
201+
</plugin>
202+
</sensor>
203+
</gazebo>
204+
205+
</xacro:macro>
206+
207+
</robot>

0 commit comments

Comments
 (0)