-
Notifications
You must be signed in to change notification settings - Fork 47
/
andino.urdf.xacro
100 lines (75 loc) · 3.87 KB
/
andino.urdf.xacro
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
92
93
94
95
96
97
98
99
100
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="andino">
<xacro:property name="package_name" value="andino_description"/>
<xacro:property name="robot_name" value="andino"/>
<xacro:include filename="$(find ${package_name})/urdf/include/common_macros.urdf.xacro" />
<xacro:include filename="$(find ${package_name})/urdf/include/common_sensors.urdf.xacro" />
<xacro:include filename="$(find ${package_name})/urdf/include/andino_caster_macro.urdf.xacro" />
<xacro:arg name="yaml_config_dir" default="$(find ${package_name})/config/${robot_name}" />
<xacro:property name="caster_wheel_yaml" value="$(arg yaml_config_dir)/caster_wheel.yaml" />
<xacro:property name="caster_wheel_props" value="${xacro.load_yaml(caster_wheel_yaml)}"/>
<xacro:arg name="use_fixed_caster" default="True"/>
<xacro:arg name="use_real_ros_control" default="True"/>
<xacro:property name="wheel_yaml" value="$(arg yaml_config_dir)/wheel.yaml" />
<xacro:property name="wheel_props" value="${xacro.load_yaml(wheel_yaml)}"/>
<xacro:property name="motor_yaml" value="$(arg yaml_config_dir)/motor.yaml" />
<xacro:property name="motor_props" value="${xacro.load_yaml(motor_yaml)}"/>
<xacro:property name="base_yaml" value="$(arg yaml_config_dir)/base.yaml" />
<xacro:property name="base_props" value="${xacro.load_yaml(base_yaml)}"/>
<xacro:property name="second_base_yaml" value="$(arg yaml_config_dir)/second_base.yaml" />
<xacro:property name="second_base_props" value="${xacro.load_yaml(second_base_yaml)}"/>
<xacro:property name="sensor_yaml" value="$(arg yaml_config_dir)/sensors.yaml" />
<xacro:property name="sensor_prop" value="${xacro.load_yaml(sensor_yaml)}"/>
<xacro:property name="hardware_yaml" value="$(arg yaml_config_dir)/hardware.yaml" />
<xacro:property name="hardware_props" value="${xacro.load_yaml(hardware_yaml)}"/>
<!-- Footprint link -->
<xacro:footprint wheel_props="${wheel_props}" />
<!-- Base link -->
<xacro:base link_name="base_link" base_prop="${base_props}" mesh="${base_props['base']['mesh']}" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:base>
<!-- Second story link -->
<xacro:base link_name="second_base_link" base_prop="${second_base_props}" mesh="${second_base_props['base']['mesh']}" >
<origin xyz="0 0 0.05" rpy="0 0 0" />
</xacro:base>
<!-- Joint to connect second_story with base_link -->
<joint name="second_base_joint" type="fixed">
<parent link="base_link"/>
<child link="second_base_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<!-- Caster Wheel -->
<xacro:caster_wheel reflect="-1"
use_fixed="$(arg use_fixed_caster)"
wheel_props="${caster_wheel_props}">
</xacro:caster_wheel>
<!-- Wheels -->
<xacro:wheel prefix="right" reflect="-1"
wheel_props="${wheel_props}"
base_props="${base_props}" >
</xacro:wheel>
<xacro:wheel prefix="left" reflect="1"
wheel_props="${wheel_props}"
base_props="${base_props}" >
</xacro:wheel>
<!-- Motors -->
<xacro:motor prefix="right" reflect="-1"
motor_props="${motor_props}"
base_props="${base_props}" >
</xacro:motor>
<xacro:motor prefix="left" reflect="1"
motor_props="${motor_props}"
base_props="${base_props}" >
</xacro:motor>
<!-- Sensors -->
<xacro:laser prefix="rplidar" parent_link="second_base_link"
sensor_prop="${sensor_prop}">
</xacro:laser>
<xacro:camera_sensor parent_link="base_link" sensor_prop="${sensor_prop}">
</xacro:camera_sensor>
<!-- ros2_control -->
<xacro:if value="$(arg use_real_ros_control)">
<xacro:include filename="$(find ${package_name})/urdf/include/andino_control.urdf.xacro" />
<xacro:control hardware_props="${hardware_props}" />
</xacro:if>
</robot>