-
Notifications
You must be signed in to change notification settings - Fork 11
/
funcs.rs
218 lines (206 loc) · 7.32 KB
/
funcs.rs
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
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
use crate::deserialize::*;
use crate::errors::*;
use std::path::Path;
/// sort <link> and <joint> to avoid the [issue](https://github.com/RReverser/serde-xml-rs/issues/5)
fn sort_link_joint(string: &str) -> Result<String> {
let e: xml::Element = string.parse().map_err(UrdfError::new)?;
let mut links = Vec::new();
let mut joints = Vec::new();
let mut materials = Vec::new();
for c in &e.children {
if let xml::Xml::ElementNode(ref xml_elm) = *c {
if xml_elm.name == "link" {
links.push(xml::Xml::ElementNode(xml_elm.clone()));
} else if xml_elm.name == "joint" {
joints.push(xml::Xml::ElementNode(xml_elm.clone()));
} else if xml_elm.name == "material" {
materials.push(xml::Xml::ElementNode(xml_elm.clone()));
}
};
}
let mut new_elm = e;
links.extend(joints);
links.extend(materials);
new_elm.children = links;
Ok(format!("{new_elm}"))
}
/// Read urdf file and create Robot instance
///
/// # Examples
///
/// ```
/// let urdf_robo = urdf_rs::read_file("sample.urdf").unwrap();
/// let links = urdf_robo.links;
/// println!("{:?}", links[0].visual[0].origin.xyz);
/// ```
pub fn read_file<P: AsRef<Path>>(path: P) -> Result<Robot> {
read_from_string(&std::fs::read_to_string(path)?)
}
/// Read from string instead of file.
///
///
/// # Examples
///
/// ```
/// let s = r##"
/// <robot name="robo">
/// <link name="shoulder1">
/// <inertial>
/// <origin xyz="0 0 0.5" rpy="0 0 0"/>
/// <mass value="1"/>
/// <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
/// </inertial>
/// <visual>
/// <origin xyz="0.1 0.2 0.3" rpy="-0.1 -0.2 -0.3" />
/// <geometry>
/// <box size="1.0 2.0 3.0" />
/// </geometry>
/// <material name="Cyan">
/// <color rgba="0 1.0 1.0 1.0"/>
/// </material>
/// </visual>
/// <collision>
/// <origin xyz="0 0 0" rpy="0 0 0"/>
/// <geometry>
/// <cylinder radius="1" length="0.5"/>
/// </geometry>
/// </collision>
/// </link>
/// <link name="elbow1" />
/// <link name="wrist1" />
/// <joint name="shoulder_pitch" type="revolute">
/// <origin xyz="0.0 0.0 0.1" />
/// <parent link="shoulder1" />
/// <child link="elbow1" />
/// <axis xyz="0 1 -1" />
/// <limit lower="-1" upper="1.0" effort="0" velocity="1.0"/>
/// </joint>
/// <joint name="shoulder_pitch" type="revolute">
/// <origin xyz="0.0 0.0 0.0" />
/// <parent link="elbow1" />
/// <child link="wrist1" />
/// <axis xyz="0 1 0" />
/// <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/>
/// </joint>
/// </robot>
/// "##;
/// let urdf_robo = urdf_rs::read_from_string(s).unwrap();
/// println!("{:?}", urdf_robo.links[0].visual[0].origin.xyz);
/// ```
pub fn read_from_string(string: &str) -> Result<Robot> {
let sorted_string = sort_link_joint(string)?;
serde_xml_rs::from_str(&sorted_string).map_err(UrdfError::new)
}
#[test]
fn it_works() {
use assert_approx_eq::assert_approx_eq;
let s = r##"
<robot name="robo">
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<link name="shoulder1">
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
</inertial>
<visual>
<origin xyz="0.1 0.2 0.3" rpy="-0.1 -0.2 -0.3" />
<geometry>
<box size="1.0 2.0 3.0" />
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
<visual>
<origin xyz="0.1 0.2 0.3" rpy="-0.1 -0.2 -0.3" />
<geometry>
<mesh filename="aa.dae" />
</geometry>
</visual>
<visual>
<origin xyz="0.1 0.2 0.3" rpy="-0.1 -0.2 -0.3" />
<geometry>
<mesh filename="bbb.dae" scale="2.0 3.0 4.0" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="1" length="0.5"/>
</geometry>
</collision>
</link>
<joint name="shoulder_pitch" type="revolute">
<origin xyz="0.0 0.0 0.1" />
<parent link="shoulder1" />
<child link="elbow1" />
<axis xyz="0 1 -1" />
<limit lower="-1" upper="1.0" effort="0" velocity="1.0"/>
</joint>
<link name="elbow1" />
<link name="wrist1" />
<joint name="shoulder_pitch" type="revolute">
<origin xyz="0.0 0.0 0.0" />
<parent link="elbow1" />
<child link="wrist1" />
<axis xyz="0 1 0" />
<limit lower="-2" upper="1.0" effort="0" velocity="1.0"/>
</joint>
</robot>
"##;
let robo = read_from_string(s).unwrap();
assert_eq!(robo.name, "robo");
assert_eq!(robo.links.len(), 3);
assert_eq!(robo.joints.len(), 2);
assert_eq!(robo.links[0].visual.len(), 3);
let xyz = robo.links[0].visual[0].origin.xyz;
assert_approx_eq!(xyz[0], 0.1);
assert_approx_eq!(xyz[1], 0.2);
assert_approx_eq!(xyz[2], 0.3);
let rpy = robo.links[0].visual[0].origin.rpy;
assert_approx_eq!(rpy[0], -0.1);
assert_approx_eq!(rpy[1], -0.2);
assert_approx_eq!(rpy[2], -0.3);
match robo.links[0].visual[0].geometry {
Geometry::Box { size } => {
assert_approx_eq!(size[0], 1.0f64);
assert_approx_eq!(size[1], 2.0f64);
assert_approx_eq!(size[2], 3.0f64);
}
_ => panic!("geometry error"),
}
match robo.links[0].visual[1].geometry {
Geometry::Mesh {
ref filename,
scale,
} => {
assert_eq!(filename, "aa.dae");
assert_eq!(scale, None);
}
_ => panic!("geometry error"),
}
match robo.links[0].visual[2].geometry {
Geometry::Mesh {
ref filename,
scale,
} => {
assert_eq!(filename, "bbb.dae");
assert!(scale.is_some());
}
_ => panic!("geometry error"),
}
assert_eq!(robo.materials.len(), 1);
assert_eq!(robo.joints[0].name, "shoulder_pitch");
let xyz = robo.joints[0].axis.xyz;
assert_approx_eq!(xyz[0], 0.0f64);
assert_approx_eq!(xyz[1], 1.0f64);
assert_approx_eq!(xyz[2], -1.0f64);
let xyz = robo.joints[0].axis.xyz;
//"0 1 -1"
assert_approx_eq!(xyz[0], 0.0);
assert_approx_eq!(xyz[1], 1.0);
assert_approx_eq!(xyz[2], -1.0);
}