Skip to content

Commit 1121b4c

Browse files
authored
Merge pull request RobotnikAutomation#29 from RobotnikAutomation/feature/normalize-axiscamera-axis
Feature/normalize axiscamera axis
2 parents 887ac72 + 7a8c39d commit 1121b4c

File tree

3 files changed

+17
-20
lines changed

3 files changed

+17
-20
lines changed

urdf/axis.urdf.xacro

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88

99
<xacro:macro name="sensor_axis" params="prefix parent *origin far:=^|8.0 near:=^|0.05">
1010
<joint name="${prefix}_joint" type="fixed">
11-
<axis xyz="0 1 0"/>
11+
<axis xyz="0 0 1"/>
1212
<xacro:insert_block name="origin"/>
1313
<parent link="${parent}"/>
1414
<child link="${prefix}_base_link"/>
@@ -38,7 +38,7 @@
3838
</collision>
3939
</link>
4040
<joint name="${prefix}_pan_joint" type="revolute">
41-
<axis xyz="0 0 -1"/>
41+
<axis xyz="0 0 1"/>
4242
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
4343
<!-- check the displacement -->
4444
<parent link="${prefix}_base_link"/>
@@ -64,8 +64,8 @@
6464
</actuator>
6565
</transmission>
6666
<joint name="${prefix}_tilt_joint" type="revolute">
67-
<axis xyz="0 -1 0"/>
68-
<origin xyz="0.0 0.0 0.0"/>
67+
<axis xyz="0 0 1"/>
68+
<origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0 0"/>
6969
<parent link="${prefix}_pan_link"/>
7070
<child link="${prefix}_tilt_link"/>
7171
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-1.5708" upper="1.5708"/>

urdf/axis_m5013.urdf.xacro

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99

1010
<xacro:macro name="sensor_axis_m5013" params="prefix parent *origin far:=^|8.0 near:=^|0.05">
1111
<joint name="${prefix}_joint" type="fixed">
12-
<axis xyz="0 1 0"/>
12+
<axis xyz="0 0 1"/>
1313
<xacro:insert_block name="origin"/>
1414
<parent link="${parent}"/>
1515
<child link="${prefix}_base_link"/>
@@ -39,8 +39,8 @@
3939
</link>
4040

4141
<joint name="${prefix}_pan_joint" type="revolute">
42-
<axis xyz="1 0 0"/>
43-
<origin xyz="0.04 0.0 0.0" rpy="0 0 0"/>
42+
<axis xyz="0 0 1"/>
43+
<origin xyz="1 0.0 0.04" rpy="0 0 0"/>
4444
<!-- check the displacement -->
4545
<parent link="${prefix}_base_link"/>
4646
<child link="${prefix}_pan_link"/>
@@ -66,8 +66,8 @@
6666
</transmission>
6767

6868
<joint name="${prefix}_tilt_joint" type="revolute">
69-
<axis xyz="0 -1 0"/>
70-
<origin xyz="0.0 0.0 0.0" rpy="0 ${-PI/2} 0"/>
69+
<axis xyz="0 0 1"/>
70+
<origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0 0"/>
7171
<parent link="${prefix}_pan_link"/>
7272
<child link="${prefix}_tilt_link"/>
7373
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-1.5708" upper="1.5708"/>

urdf/axis_m5525.urdf.xacro

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -9,22 +9,19 @@
99

1010
<xacro:macro name="sensor_axis_m5525" params="prefix parent *origin far:=^|8.0 near:=^|0.05 prefix_topic:=^ptz_camera">
1111
<joint name="${prefix}_joint" type="fixed">
12-
<axis xyz="0 1 0"/>
13-
<!--
14-
<origin xyz="0.180 0.0 0.270"/>
15-
-->
12+
<axis xyz="0 0 1"/>
1613
<xacro:insert_block name="origin"/>
1714
<parent link="${parent}"/>
1815
<child link="${prefix}_base_link"/>
1916
</joint>
2017
<link name="${prefix}_base_link">
2118
<inertial>
22-
<origin xyz="0.066 0 0" rpy="0 ${M_PI/2} 0"/>
19+
<origin xyz="0.066 0 0" rpy="0 0 0"/>
2320
<mass value="0.8"/>
2421
<xacro:solid_cuboid_inertia m="0.8" w="0.165" h="0.165" d="0.132" />
2522
</inertial>
2623
<visual>
27-
<origin xyz="0 0 0" rpy="0 ${M_PI/2} 0"/>
24+
<origin xyz="0 0 0" rpy="0 0 0"/>
2825
<!-- to center the axis model -->
2926
<material name="axis_color">
3027
<color rgba="0.1 0.1 0.1 1"/>
@@ -34,16 +31,16 @@
3431
</geometry>
3532
</visual>
3633
<collision>
37-
<origin xyz="0.0 0.0 0" rpy="0 ${M_PI/2} 0"/>
34+
<origin xyz="0.0 0.0 0" rpy="0 0 0"/>
3835
<geometry>
3936
<mesh filename="package://robotnik_sensors/meshes/axis_m5525.stl" scale="1.0 1.0 1.0"/>
4037
</geometry>
4138
</collision>
4239
</link>
4340

4441
<joint name="${prefix}_pan_joint" type="revolute">
45-
<axis xyz="1 0 0"/>
46-
<origin xyz="0.087 0.0 0.0" rpy="0 0 0"/>
42+
<axis xyz="0 0 1"/>
43+
<origin xyz="0 0.0 0.087" rpy="0 0 0"/>
4744
<!-- check the displacement -->
4845
<parent link="${prefix}_base_link"/>
4946
<child link="${prefix}_pan_link"/>
@@ -68,8 +65,8 @@
6865
</actuator>
6966
</transmission>
7067
<joint name="${prefix}_tilt_joint" type="revolute">
71-
<axis xyz="0 -1 0"/>
72-
<origin xyz="0.0 0.0 0.0" rpy="0 ${-PI/2} 0"/>
68+
<axis xyz="0 0 1"/>
69+
<origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0 0"/>
7370
<parent link="${prefix}_pan_link"/>
7471
<child link="${prefix}_tilt_link"/>
7572
<limit effort="${ptz_joint_effort_limit}" velocity="${ptz_joint_velocity_limit}" lower="-1.5708" upper="1.5708"/>

0 commit comments

Comments
 (0)