|
21 | 21 | name
|
22 | 22 | parent_link
|
23 | 23 | cap:=halo
|
| 24 | + base:=base |
24 | 25 | *origin
|
25 | 26 | samples_h:=1024 min_ang_h:=${-pi} max_ang_h:=${pi}
|
26 | 27 | samples_v:=64 min_ang_v:=${-21.2 * pi/180} max_ang_v:=${21.2 * pi/180}
|
|
32 | 33 | <xacro:property name="lidar_height" value="0.05835"/>
|
33 | 34 | <xacro:property name="lidar_diameter" value="0.087"/>
|
34 | 35 |
|
35 |
| - <xacro:property name="base_mass" value="0."/> |
36 |
| - <xacro:property name="base_height" value="0.0225"/> |
37 |
| - <xacro:property name="base_length" value="0.110"/> |
| 36 | + <xacro:if value="${base == 'base'}"> |
| 37 | + <xacro:property name="base_mass" value="0.0"/> |
| 38 | + <xacro:property name="base_height" value="0.0225"/> |
| 39 | + <xacro:property name="base_length" value="0.110"/> |
| 40 | + </xacro:if> |
| 41 | + <xacro:unless value="${base == 'base'}"> |
| 42 | + <xacro:property name="base_mass" value="0.0"/> |
| 43 | + <xacro:property name="base_height" value="0.0"/> |
| 44 | + <xacro:property name="base_length" value="0.0"/> |
| 45 | + </xacro:unless> |
38 | 46 |
|
39 | 47 | <xacro:property name="fins_mass" value="0.079"/>
|
40 | 48 | <xacro:property name="fins_height" value="0.022"/>
|
|
46 | 54 |
|
47 | 55 |
|
48 | 56 | <!-- Base Link -->
|
49 |
| - <link name="${name}_base_link"> |
50 |
| - <inertial> |
51 |
| - <mass value="${base_mass}"/> |
52 |
| - <origin xyz="0 0 ${base_height/2}"/> |
53 |
| - <xacro:ouster_box_inertia |
54 |
| - mass="${base_mass}" |
55 |
| - x="${base_length}" |
56 |
| - y="${base_length}" |
57 |
| - z="${base_height}" |
58 |
| - /> |
59 |
| - </inertial> |
60 |
| - <visual> |
61 |
| - <material name="ouster_grey"> |
62 |
| - <color rgba="0.8 0.8 0.8 1.0"/> |
63 |
| - </material> |
64 |
| - <origin xyz="0 0 ${base_height}"/> |
65 |
| - <geometry> |
66 |
| - <mesh filename="package://clearpath_sensors_description/meshes/ouster/os1_base.dae"/> |
67 |
| - </geometry> |
68 |
| - </visual> |
69 |
| - <collision> |
70 |
| - <origin xyz="0 0 ${base_height/2}"/> |
71 |
| - <geometry> |
72 |
| - <box size="${base_length} ${base_length} ${base_height}"/> |
73 |
| - </geometry> |
74 |
| - </collision> |
75 |
| - </link> |
| 57 | + <xacro:if value="${base == 'base'}"> |
| 58 | + <link name="${name}_base_link"> |
| 59 | + <inertial> |
| 60 | + <mass value="${base_mass}"/> |
| 61 | + <origin xyz="0 0 ${base_height/2}"/> |
| 62 | + <xacro:ouster_box_inertia |
| 63 | + mass="${base_mass}" |
| 64 | + x="${base_length}" |
| 65 | + y="${base_length}" |
| 66 | + z="${base_height}" |
| 67 | + /> |
| 68 | + </inertial> |
| 69 | + <visual> |
| 70 | + <material name="ouster_grey"> |
| 71 | + <color rgba="0.8 0.8 0.8 1.0"/> |
| 72 | + </material> |
| 73 | + <origin xyz="0 0 ${base_height}"/> |
| 74 | + <geometry> |
| 75 | + <mesh filename="package://clearpath_sensors_description/meshes/ouster/os1_base.dae"/> |
| 76 | + </geometry> |
| 77 | + </visual> |
| 78 | + <collision> |
| 79 | + <origin xyz="0 0 ${base_height/2}"/> |
| 80 | + <geometry> |
| 81 | + <box size="${base_length} ${base_length} ${base_height}"/> |
| 82 | + </geometry> |
| 83 | + </collision> |
| 84 | + </link> |
| 85 | + </xacro:if> |
| 86 | + <xacro:unless value="${base == 'base'}"> |
| 87 | + <link name="${name}_base_link" /> |
| 88 | + </xacro:unless> |
76 | 89 |
|
77 | 90 | <!-- Lidar Link -->
|
78 | 91 | <link name="${name}_link">
|
|
0 commit comments