-
Notifications
You must be signed in to change notification settings - Fork 8
/
diffbot.urdf.xacro
47 lines (33 loc) · 1.85 KB
/
diffbot.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mobile_robot">
<xacro:property name="package_name" value="mobile_robot_description"/>
<xacro:property name="robot_name" value="diffbot"/>
<xacro:include filename="$(find ${package_name})/urdf/include/common_macros.urdf.xacro" />
<!-- <xacro:set_package_name /> -->
<xacro:property name="caster_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/caster_wheel.yaml" />
<xacro:property name="caster_wheel_props" value="${load_yaml(caster_wheel_yaml)}"/>
<xacro:property name="front_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/front_wheel.yaml" />
<xacro:property name="front_wheel_props" value="${load_yaml(front_wheel_yaml)}"/>
<xacro:property name="base_yaml" value="$(find ${package_name})/config/${robot_name}/base.yaml" />
<xacro:property name="base_props" value="${load_yaml(base_yaml)}"/>
<!-- Base link -->
<xacro:base base_prop="${base_props}" mesh="${base_props['base']['mesh']}" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:base>
<!-- Back Caster Wheel -->
<xacro:caster_wheel prefix="caster_wheel" reflect="-1"
wheel_props="${caster_wheel_props}">
</xacro:caster_wheel>
<!-- Front Wheels -->
<xacro:wheel prefix="front_right" reflect="-1"
wheel_props="${front_wheel_props}"
base_props="${base_props}"
mesh="${front_wheel_props['wheel']['mesh']}">
</xacro:wheel>
<xacro:wheel prefix="front_left" reflect="1"
wheel_props="${front_wheel_props}"
base_props="${base_props}"
mesh="${front_wheel_props['wheel']['mesh']}">
</xacro:wheel>
<!-- <xacro:include filename="$(find mobile_description)/urdf/mobile_robot_gazebo_plugins.xacro"/> -->
</robot>