File tree 1 file changed +57
-0
lines changed
1 file changed +57
-0
lines changed Original file line number Diff line number Diff line change 373
373
</ode >
374
374
</physics >
375
375
</joint >
376
+ <include merge =' true' >
377
+ <uri >model://LW20</uri >
378
+ <pose relative_to =" base_link" >0.05 0 -0.1 0 1.57 0</pose >
379
+ </include >
380
+
381
+ <joint name =" lidar_model_joint" type =" fixed" >
382
+ <parent >base_link</parent >
383
+ <child >lw20_link</child >
384
+ <pose relative_to =" base_link" >0 0 0 0 0 0</pose >
385
+ </joint >
386
+
387
+ <joint name =" lidar_sensor_joint" type =" fixed" >
388
+ <parent >base_link</parent >
389
+ <child >lidar_sensor_link</child >
390
+ </joint >
391
+
392
+ <link name =" lidar_sensor_link" >
393
+ <pose relative_to =" base_link" >0.05 0 0 0 1.57 0</pose >
394
+ <inertial >
395
+ <mass >0.001</mass >
396
+ <inertia >
397
+ <ixx >0.00001</ixx >
398
+ <iyy >0.00001</iyy >
399
+ <izz >0.00001</izz >
400
+ <ixy >0.0</ixy >
401
+ <ixz >0.0</ixz >
402
+ <iyz >0.0</iyz >
403
+ </inertia >
404
+ </inertial >
405
+ <sensor name =' lidar' type =' gpu_lidar' >
406
+ <pose >0 0 0 0 0 0</pose >
407
+ <update_rate >50</update_rate >
408
+ <ray >
409
+ <scan >
410
+ <horizontal >
411
+ <samples >1</samples >
412
+ <resolution >1</resolution >
413
+ <min_angle >0</min_angle >
414
+ <max_angle >0</max_angle >
415
+ </horizontal >
416
+ <vertical >
417
+ <samples >1</samples >
418
+ <resolution >1</resolution >
419
+ <min_angle >0</min_angle >
420
+ <max_angle >0</max_angle >
421
+ </vertical >
422
+ </scan >
423
+ <range >
424
+ <min >0.1</min >
425
+ <max >100.0</max >
426
+ <resolution >0.01</resolution >
427
+ </range >
428
+ </ray >
429
+ <always_on >1</always_on >
430
+ <visualize >true</visualize >
431
+ </sensor >
432
+ </link >
376
433
<plugin
377
434
filename =" gz-sim-joint-position-controller-system" name =" gz::sim::systems::JointPositionController" >
378
435
<joint_name >servo_0</joint_name >
You can’t perform that action at this time.
0 commit comments