File size: 2,570 Bytes
44319b1
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
<?xml version="1.0"?>
<robot name="rocker_switch">

  <!-- Materials -->
  <material name="mat_black"><color rgba="0.08 0.08 0.08 1.0"/></material>
  <material name="mat_gray"><color rgba="0.45 0.45 0.48 1.0"/></material>

  <!-- Root base for the standalone switch -->
  <link name="switch_base_link">
    <inertial>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <mass value="0.08"/>
      <inertia ixx="0.00006" ixy="0.0" ixz="0.0"
               iyy="0.00006" iyz="0.0"
               izz="0.00008"/>
    </inertial>

    <visual>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <geometry><box size="0.07 0.05 0.012"/></geometry>
      <material name="mat_black"/>
    </visual>

    <collision>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <geometry><box size="0.07 0.05 0.012"/></geometry>
    </collision>
  </link>

  <!-- Rocker Switch housing -->
  <link name="switch_housing_link">
    <inertial>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <mass value="0.05"/>
      <inertia ixx="0.00002" ixy="0.0" ixz="0.0"
               iyy="0.00002" iyz="0.0"
               izz="0.00002"/>
    </inertial>

    <visual>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <geometry><box size="0.05 0.03 0.012"/></geometry>
      <material name="mat_gray"/>
    </visual>

    <collision>
      <origin xyz="0 0 0.006" rpy="0 0 0"/>
      <geometry><box size="0.05 0.03 0.012"/></geometry>
    </collision>
  </link>

  <joint name="switch_housing_joint" type="fixed">
    <parent link="switch_base_link"/>
    <child link="switch_housing_link"/>
    <!-- centered on the base -->
    <origin xyz="0 0 0.012" rpy="0 0 0"/>
  </joint>

  <!-- Rocker toggle -->
  <link name="rocker_link">
    <inertial>
      <origin xyz="0 0 0.004" rpy="0 0 0"/>
      <mass value="0.02"/>
      <inertia ixx="0.000005" ixy="0.0" ixz="0.0"
               iyy="0.000004" iyz="0.0"
               izz="0.000006"/>
    </inertial>

    <visual>
      <origin xyz="0 0 0.004" rpy="0 0 0"/>
      <geometry><box size="0.042 0.024 0.008"/></geometry>
      <material name="mat_black"/>
    </visual>

    <collision>
      <origin xyz="0 0 0.004" rpy="0 0 0"/>
      <geometry><box size="0.042 0.024 0.008"/></geometry>
    </collision>
  </link>

  <joint name="rocker_joint" type="revolute">
    <parent link="switch_housing_link"/>
    <child link="rocker_link"/>
    <origin xyz="0 0 0.010" rpy="0 0 0"/>
    <axis xyz="0 1 0"/>
    <limit lower="-0.436332" upper="0.436332" effort="0.3" velocity="3.0"/>
    <dynamics damping="0.03" friction="0.02"/>
  </joint>

</robot>