|
| 1 | +<?xml version="1.0"?> |
| 2 | +<robot xmlns:xacro="http://ros.org/wiki/xacro"> |
| 3 | + <xacro:macro name="sensor_kit_macro" params="parent x y z roll pitch yaw"> |
| 4 | + <xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/> |
| 5 | + <xacro:include filename="$(find vls_description)/urdf/VLS-128.urdf.xacro"/> |
| 6 | + <xacro:include filename="$(find camera_description)/urdf/monocular_camera.xacro"/> |
| 7 | + <xacro:include filename="$(find imu_description)/urdf/imu.xacro"/> |
| 8 | + |
| 9 | + <xacro:arg name="gpu" default="false"/> |
| 10 | + <xacro:arg name="config_dir" default="$(find awsim_labs_sensor_kit_description)/config"/> |
| 11 | + |
| 12 | + <xacro:property name="sensor_kit_base_link" default="sensor_kit_base_link"/> |
| 13 | + |
| 14 | + <joint name="${sensor_kit_base_link}_joint" type="fixed"> |
| 15 | + <origin rpy="${roll} ${pitch} ${yaw}" xyz="${x} ${y} ${z}"/> |
| 16 | + <parent link="${parent}"/> |
| 17 | + <child link="${sensor_kit_base_link}"/> |
| 18 | + </joint> |
| 19 | + <link name="${sensor_kit_base_link}"> |
| 20 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 21 | + </link> |
| 22 | + |
| 23 | + <!-- sensor --> |
| 24 | + <xacro:property name="calibration" value="${xacro.load_yaml('$(arg config_dir)/sensor_kit_calibration.yaml')}"/> |
| 25 | + |
| 26 | + <!-- lidar --> |
| 27 | + <xacro:VLS-128 parent="sensor_kit_base_link" name="velodyne_top" topic="/points_raw" hz="10" samples="220" gpu="$(arg gpu)"> |
| 28 | + <origin |
| 29 | + xyz="${calibration['sensor_kit_base_link']['velodyne_top_base_link']['x']} |
| 30 | + ${calibration['sensor_kit_base_link']['velodyne_top_base_link']['y']} |
| 31 | + ${calibration['sensor_kit_base_link']['velodyne_top_base_link']['z']}" |
| 32 | + rpy="${calibration['sensor_kit_base_link']['velodyne_top_base_link']['roll']} |
| 33 | + ${calibration['sensor_kit_base_link']['velodyne_top_base_link']['pitch']} |
| 34 | + ${calibration['sensor_kit_base_link']['velodyne_top_base_link']['yaw']}" |
| 35 | + /> |
| 36 | + </xacro:VLS-128> |
| 37 | + <xacro:VLP-16 parent="sensor_kit_base_link" name="velodyne_left" topic="/points_raw" hz="10" samples="220" gpu="$(arg gpu)"> |
| 38 | + <origin |
| 39 | + xyz="${calibration['sensor_kit_base_link']['velodyne_left_base_link']['x']} |
| 40 | + ${calibration['sensor_kit_base_link']['velodyne_left_base_link']['y']} |
| 41 | + ${calibration['sensor_kit_base_link']['velodyne_left_base_link']['z']}" |
| 42 | + rpy="${calibration['sensor_kit_base_link']['velodyne_left_base_link']['roll']} |
| 43 | + ${calibration['sensor_kit_base_link']['velodyne_left_base_link']['pitch']} |
| 44 | + ${calibration['sensor_kit_base_link']['velodyne_left_base_link']['yaw']}" |
| 45 | + /> |
| 46 | + </xacro:VLP-16> |
| 47 | + <xacro:VLP-16 parent="sensor_kit_base_link" name="velodyne_right" topic="/points_raw" hz="10" samples="220" gpu="$(arg gpu)"> |
| 48 | + <origin |
| 49 | + xyz="${calibration['sensor_kit_base_link']['velodyne_right_base_link']['x']} |
| 50 | + ${calibration['sensor_kit_base_link']['velodyne_right_base_link']['y']} |
| 51 | + ${calibration['sensor_kit_base_link']['velodyne_right_base_link']['z']}" |
| 52 | + rpy="${calibration['sensor_kit_base_link']['velodyne_right_base_link']['roll']} |
| 53 | + ${calibration['sensor_kit_base_link']['velodyne_right_base_link']['pitch']} |
| 54 | + ${calibration['sensor_kit_base_link']['velodyne_right_base_link']['yaw']}" |
| 55 | + /> |
| 56 | + </xacro:VLP-16> |
| 57 | + |
| 58 | + <!-- camera --> |
| 59 | + <xacro:monocular_camera_macro |
| 60 | + name="traffic_light_right_camera/camera" |
| 61 | + parent="sensor_kit_base_link" |
| 62 | + namespace="" |
| 63 | + x="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['x']}" |
| 64 | + y="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['y']}" |
| 65 | + z="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['z']}" |
| 66 | + roll="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['roll']}" |
| 67 | + pitch="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['pitch']}" |
| 68 | + yaw="${calibration['sensor_kit_base_link']['traffic_light_right_camera/camera_link']['yaw']}" |
| 69 | + fps="30" |
| 70 | + width="800" |
| 71 | + height="400" |
| 72 | + fov="1.3" |
| 73 | + /> |
| 74 | + <xacro:monocular_camera_macro |
| 75 | + name="traffic_light_left_camera/camera" |
| 76 | + parent="sensor_kit_base_link" |
| 77 | + namespace="" |
| 78 | + x="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['x']}" |
| 79 | + y="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['y']}" |
| 80 | + z="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['z']}" |
| 81 | + roll="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['roll']}" |
| 82 | + pitch="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['pitch']}" |
| 83 | + yaw="${calibration['sensor_kit_base_link']['traffic_light_left_camera/camera_link']['yaw']}" |
| 84 | + fps="30" |
| 85 | + width="800" |
| 86 | + height="400" |
| 87 | + fov="1.3" |
| 88 | + /> |
| 89 | + <xacro:monocular_camera_macro |
| 90 | + name="camera0/camera" |
| 91 | + parent="sensor_kit_base_link" |
| 92 | + namespace="" |
| 93 | + x="${calibration['sensor_kit_base_link']['camera0/camera_link']['x']}" |
| 94 | + y="${calibration['sensor_kit_base_link']['camera0/camera_link']['y']}" |
| 95 | + z="${calibration['sensor_kit_base_link']['camera0/camera_link']['z']}" |
| 96 | + roll="${calibration['sensor_kit_base_link']['camera0/camera_link']['roll']}" |
| 97 | + pitch="${calibration['sensor_kit_base_link']['camera0/camera_link']['pitch']}" |
| 98 | + yaw="${calibration['sensor_kit_base_link']['camera0/camera_link']['yaw']}" |
| 99 | + fps="30" |
| 100 | + width="800" |
| 101 | + height="400" |
| 102 | + fov="1.3" |
| 103 | + /> |
| 104 | + <xacro:monocular_camera_macro |
| 105 | + name="camera1/camera" |
| 106 | + parent="sensor_kit_base_link" |
| 107 | + namespace="" |
| 108 | + x="${calibration['sensor_kit_base_link']['camera1/camera_link']['x']}" |
| 109 | + y="${calibration['sensor_kit_base_link']['camera1/camera_link']['y']}" |
| 110 | + z="${calibration['sensor_kit_base_link']['camera1/camera_link']['z']}" |
| 111 | + roll="${calibration['sensor_kit_base_link']['camera1/camera_link']['roll']}" |
| 112 | + pitch="${calibration['sensor_kit_base_link']['camera1/camera_link']['pitch']}" |
| 113 | + yaw="${calibration['sensor_kit_base_link']['camera1/camera_link']['yaw']}" |
| 114 | + fps="30" |
| 115 | + width="800" |
| 116 | + height="400" |
| 117 | + fov="1.3" |
| 118 | + /> |
| 119 | + <xacro:monocular_camera_macro |
| 120 | + name="camera2/camera" |
| 121 | + parent="sensor_kit_base_link" |
| 122 | + namespace="" |
| 123 | + x="${calibration['sensor_kit_base_link']['camera2/camera_link']['x']}" |
| 124 | + y="${calibration['sensor_kit_base_link']['camera2/camera_link']['y']}" |
| 125 | + z="${calibration['sensor_kit_base_link']['camera2/camera_link']['z']}" |
| 126 | + roll="${calibration['sensor_kit_base_link']['camera2/camera_link']['roll']}" |
| 127 | + pitch="${calibration['sensor_kit_base_link']['camera2/camera_link']['pitch']}" |
| 128 | + yaw="${calibration['sensor_kit_base_link']['camera2/camera_link']['yaw']}" |
| 129 | + fps="30" |
| 130 | + width="800" |
| 131 | + height="400" |
| 132 | + fov="1.3" |
| 133 | + /> |
| 134 | + <xacro:monocular_camera_macro |
| 135 | + name="camera3/camera" |
| 136 | + parent="sensor_kit_base_link" |
| 137 | + namespace="" |
| 138 | + x="${calibration['sensor_kit_base_link']['camera3/camera_link']['x']}" |
| 139 | + y="${calibration['sensor_kit_base_link']['camera3/camera_link']['y']}" |
| 140 | + z="${calibration['sensor_kit_base_link']['camera3/camera_link']['z']}" |
| 141 | + roll="${calibration['sensor_kit_base_link']['camera3/camera_link']['roll']}" |
| 142 | + pitch="${calibration['sensor_kit_base_link']['camera3/camera_link']['pitch']}" |
| 143 | + yaw="${calibration['sensor_kit_base_link']['camera3/camera_link']['yaw']}" |
| 144 | + fps="30" |
| 145 | + width="800" |
| 146 | + height="400" |
| 147 | + fov="1.3" |
| 148 | + /> |
| 149 | + <xacro:monocular_camera_macro |
| 150 | + name="camera4/camera" |
| 151 | + parent="sensor_kit_base_link" |
| 152 | + namespace="" |
| 153 | + x="${calibration['sensor_kit_base_link']['camera4/camera_link']['x']}" |
| 154 | + y="${calibration['sensor_kit_base_link']['camera4/camera_link']['y']}" |
| 155 | + z="${calibration['sensor_kit_base_link']['camera4/camera_link']['z']}" |
| 156 | + roll="${calibration['sensor_kit_base_link']['camera4/camera_link']['roll']}" |
| 157 | + pitch="${calibration['sensor_kit_base_link']['camera4/camera_link']['pitch']}" |
| 158 | + yaw="${calibration['sensor_kit_base_link']['camera4/camera_link']['yaw']}" |
| 159 | + fps="30" |
| 160 | + width="800" |
| 161 | + height="400" |
| 162 | + fov="1.3" |
| 163 | + /> |
| 164 | + <xacro:monocular_camera_macro |
| 165 | + name="camera5/camera" |
| 166 | + parent="sensor_kit_base_link" |
| 167 | + namespace="" |
| 168 | + x="${calibration['sensor_kit_base_link']['camera5/camera_link']['x']}" |
| 169 | + y="${calibration['sensor_kit_base_link']['camera5/camera_link']['y']}" |
| 170 | + z="${calibration['sensor_kit_base_link']['camera5/camera_link']['z']}" |
| 171 | + roll="${calibration['sensor_kit_base_link']['camera5/camera_link']['roll']}" |
| 172 | + pitch="${calibration['sensor_kit_base_link']['camera5/camera_link']['pitch']}" |
| 173 | + yaw="${calibration['sensor_kit_base_link']['camera5/camera_link']['yaw']}" |
| 174 | + fps="30" |
| 175 | + width="800" |
| 176 | + height="400" |
| 177 | + fov="1.3" |
| 178 | + /> |
| 179 | + |
| 180 | + <!-- gnss --> |
| 181 | + <xacro:imu_macro |
| 182 | + name="gnss" |
| 183 | + parent="sensor_kit_base_link" |
| 184 | + namespace="" |
| 185 | + x="${calibration['sensor_kit_base_link']['gnss_link']['x']}" |
| 186 | + y="${calibration['sensor_kit_base_link']['gnss_link']['y']}" |
| 187 | + z="${calibration['sensor_kit_base_link']['gnss_link']['z']}" |
| 188 | + roll="${calibration['sensor_kit_base_link']['gnss_link']['roll']}" |
| 189 | + pitch="${calibration['sensor_kit_base_link']['gnss_link']['pitch']}" |
| 190 | + yaw="${calibration['sensor_kit_base_link']['gnss_link']['yaw']}" |
| 191 | + fps="100" |
| 192 | + /> |
| 193 | + |
| 194 | + <!-- imu --> |
| 195 | + <xacro:imu_macro |
| 196 | + name="tamagawa/imu" |
| 197 | + parent="sensor_kit_base_link" |
| 198 | + namespace="" |
| 199 | + x="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['x']}" |
| 200 | + y="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['y']}" |
| 201 | + z="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['z']}" |
| 202 | + roll="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['roll']}" |
| 203 | + pitch="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['pitch']}" |
| 204 | + yaw="${calibration['sensor_kit_base_link']['tamagawa/imu_link']['yaw']}" |
| 205 | + fps="100" |
| 206 | + /> |
| 207 | + </xacro:macro> |
| 208 | +</robot> |
0 commit comments