Skip to content

Commit d35bf5c

Browse files
committed
WIP Towards adding an SDFormat parser to this repo.
1 parent 7612ebb commit d35bf5c

13 files changed

+532
-121
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ Only [link](http://wiki.ros.org/urdf/XML/link) and [joint](http://wiki.ros.org/u
1111
You can access urdf elements like below example.
1212

1313
```rust
14-
let urdf_robo = urdf_rs::read_file("sample.urdf").unwrap();
14+
let urdf_robo = urdf_rs::urdf::read_file("samples/sample.urdf").unwrap();
1515
let links = urdf_robo.links;
1616
println!("{:?}", links[0].visual[0].origin.xyz);
1717
let joints = urdf_robo.joints;
File renamed without changes.

src/common/elements.rs

Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
use serde::Deserialize;
2+
use crate::common::space_seperated_vectors::*;
3+
4+
#[derive(Debug, Deserialize, Default, Clone)]
5+
pub struct Mass {
6+
pub value: f64,
7+
}
8+
9+
#[derive(Deserialize, Debug, Clone)]
10+
pub struct Vec3 {
11+
#[serde(with = "ss_vec3")]
12+
pub data: [f64; 3],
13+
}
14+
15+
#[derive(Debug, Deserialize, Default, Clone)]
16+
pub struct ColorRGBA {
17+
#[serde(with = "ss_vec4")]
18+
pub rgba: [f64; 4],
19+
}
20+
21+
22+
#[derive(Debug, Deserialize, Default, Clone)]
23+
pub struct ColorRGB {
24+
#[serde(with = "ss_vec3")]
25+
pub rgba: [f64; 3],
26+
}
27+
28+
#[derive(Debug, Deserialize, Clone)]
29+
pub struct Texture {
30+
pub filename: String,
31+
}
32+
33+
impl Default for Texture {
34+
fn default() -> Texture {
35+
Texture {
36+
filename: "".to_string(),
37+
}
38+
}
39+
}

src/common/mod.rs

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
mod elements;
2+
pub use elements::*;
3+
4+
mod space_seperated_vectors;
5+
pub use space_seperated_vectors::*;

src/common/space_seperated_vectors.rs

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
pub mod ss_vec3 {
2+
use serde::{self, Deserialize, Deserializer};
3+
pub fn deserialize<'a, D>(deserializer: D) -> Result<[f64; 3], D::Error>
4+
where
5+
D: Deserializer<'a>,
6+
{
7+
let s = String::deserialize(deserializer)?;
8+
let vec = s
9+
.split(' ')
10+
.filter_map(|x| x.parse::<f64>().ok())
11+
.collect::<Vec<_>>();
12+
if vec.len() != 3 {
13+
return Err(serde::de::Error::custom(format!(
14+
"failed to parse float array in {s}"
15+
)));
16+
}
17+
let mut arr = [0.0f64; 3];
18+
arr.copy_from_slice(&vec);
19+
Ok(arr)
20+
}
21+
}
22+
23+
pub mod ss_option_vec3 {
24+
use serde::{self, Deserialize, Deserializer};
25+
pub fn deserialize<'a, D>(deserializer: D) -> Result<Option<[f64; 3]>, D::Error>
26+
where
27+
D: Deserializer<'a>,
28+
{
29+
let s = String::deserialize(deserializer)?;
30+
let vec = s
31+
.split(' ')
32+
.filter_map(|x| x.parse::<f64>().ok())
33+
.collect::<Vec<_>>();
34+
if vec.is_empty() {
35+
Ok(None)
36+
} else if vec.len() == 3 {
37+
let mut arr = [0.0; 3];
38+
arr.copy_from_slice(&vec);
39+
Ok(Some(arr))
40+
} else {
41+
Err(serde::de::Error::custom(format!(
42+
"failed to parse float array in {s}"
43+
)))
44+
}
45+
}
46+
}
47+
48+
pub mod ss_vec4 {
49+
use serde::{self, Deserialize, Deserializer};
50+
pub fn deserialize<'a, D>(deserializer: D) -> Result<[f64; 4], D::Error>
51+
where
52+
D: Deserializer<'a>,
53+
{
54+
let s = String::deserialize(deserializer)?;
55+
let vec = s
56+
.split(' ')
57+
.filter_map(|x| x.parse::<f64>().ok())
58+
.collect::<Vec<_>>();
59+
if vec.len() != 4 {
60+
return Err(serde::de::Error::custom(format!(
61+
"failed to parse float array in {s}"
62+
)));
63+
}
64+
let mut arr = [0.0f64; 4];
65+
arr.copy_from_slice(&vec);
66+
Ok(arr)
67+
}
68+
}

src/lib.rs

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,8 @@
11
#![doc = include_str!("../README.md")]
22
#![warn(missing_debug_implementations, rust_2018_idioms)]
33

4+
mod common;
45
mod errors;
5-
pub use errors::*;
6-
7-
mod deserialize;
8-
pub use deserialize::*;
9-
10-
mod funcs;
11-
pub use funcs::*;
12-
13-
pub mod utils;
6+
pub mod urdf;
7+
pub mod sdf;
8+
pub mod ros_utils;

src/utils.rs renamed to src/ros_utils.rs

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,9 @@
1-
use crate::deserialize::Robot;
1+
//! ROS-specific functions that make use of `rosrun` and `rospack` as
2+
//! subprocesses.
3+
4+
use crate::urdf::Robot;
5+
use crate::urdf::{read_from_string, read_file};
26
use crate::errors::*;
3-
use crate::funcs::*;
47

58
use once_cell::sync::Lazy;
69
use regex::Regex;
@@ -91,6 +94,6 @@ fn it_works() {
9194
expand_package_path("/home/aaa.obj", Some(Path::new(""))),
9295
"/home/aaa.obj"
9396
);
94-
assert!(read_urdf_or_xacro("sample.urdf").is_ok());
97+
assert!(read_urdf_or_xacro("samples/sample.urdf").is_ok());
9598
assert!(read_urdf_or_xacro("sample_urdf").is_err());
9699
}

src/sdf/deserialize.rs

Lines changed: 165 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,165 @@
1+
use serde::Deserialize;
2+
use crate::common::*;
3+
4+
#[derive(Debug, Deserialize, Clone)]
5+
#[serde(rename_all = "snake_case")]
6+
pub enum Geometry {
7+
Empty,
8+
Box {
9+
#[serde(with = "ss_vec3")]
10+
size: [f64; 3],
11+
},
12+
Capsule {
13+
radius: f64,
14+
length: f64,
15+
},
16+
Cylinder {
17+
radius: f64,
18+
length: f64,
19+
},
20+
// Ellipsoid,
21+
// Heightmap,
22+
// Image,
23+
Mesh {
24+
filename: String,
25+
#[serde(with = "crate::common::ss_option_vec3", default)]
26+
scale: Option<[f64; 3]>,
27+
},
28+
// Plane,
29+
// Polyline,
30+
Sphere {
31+
radius: f64,
32+
},
33+
}
34+
35+
impl Default for Geometry {
36+
fn default() -> Geometry {
37+
Geometry::Box {
38+
size: [0.0f64, 0.0, 0.0],
39+
}
40+
}
41+
}
42+
43+
#[derive(Debug, Deserialize, Default, Clone)]
44+
pub struct Material {
45+
pub name: String,
46+
pub color: Option<ColorRGBA>,
47+
pub texture: Option<Texture>,
48+
}
49+
50+
#[derive(Debug, Deserialize, Default, Clone)]
51+
pub struct Visual {
52+
pub name: Option<String>,
53+
#[serde(default)]
54+
pub origin: Pose,
55+
pub geometry: Geometry,
56+
pub material: Option<Material>,
57+
}
58+
59+
/// Urdf Link element
60+
/// See <http://wiki.ros.org/urdf/XML/link> for more detail.
61+
#[derive(Debug, Deserialize, Clone)]
62+
pub struct Link {
63+
pub name: String,
64+
#[serde(default)]
65+
pub pose: Pose,
66+
#[serde(default)]
67+
pub visual: Vec<Visual>,
68+
}
69+
70+
#[derive(Debug, Deserialize, Clone)]
71+
pub struct Axis {
72+
#[serde(with = "crate::common::ss_vec3")]
73+
pub xyz: [f64; 3],
74+
}
75+
76+
impl Default for Axis {
77+
fn default() -> Axis {
78+
Axis {
79+
xyz: [0.0f64, 0.0, 1.0],
80+
}
81+
}
82+
}
83+
84+
#[derive(Debug, Deserialize, Clone)]
85+
pub struct Pose {
86+
#[serde(with = "crate::common::ss_vec3")]
87+
#[serde(default = "default_zero3")]
88+
pub xyz: [f64; 3],
89+
#[serde(with = "crate::common::ss_vec3")]
90+
#[serde(default = "default_zero3")]
91+
pub rpy: [f64; 3],
92+
}
93+
94+
fn default_zero3() -> [f64; 3] {
95+
[0.0f64, 0.0, 0.0]
96+
}
97+
98+
impl Default for Pose {
99+
fn default() -> Pose {
100+
Pose {
101+
xyz: default_zero3(),
102+
rpy: default_zero3(),
103+
}
104+
}
105+
}
106+
107+
#[derive(Debug, Deserialize, Clone)]
108+
pub struct LinkName {
109+
pub link: String,
110+
}
111+
112+
#[derive(Debug, Deserialize, Clone, PartialEq, Eq)]
113+
#[serde(rename_all = "snake_case")]
114+
pub enum JointType {
115+
Revolute,
116+
Continuous,
117+
Prismatic,
118+
Fixed,
119+
Floating,
120+
Planar,
121+
Spherical,
122+
}
123+
124+
#[derive(Debug, Deserialize, Default, Clone)]
125+
pub struct JointLimit {
126+
#[serde(default)]
127+
pub lower: f64,
128+
#[serde(default)]
129+
pub upper: f64,
130+
pub effort: f64,
131+
pub velocity: f64,
132+
}
133+
134+
/// Urdf Joint element
135+
/// See <http://wiki.ros.org/urdf/XML/joint> for more detail.
136+
#[derive(Debug, Deserialize, Clone)]
137+
pub struct Joint {
138+
pub name: String,
139+
#[serde(rename = "type")]
140+
pub joint_type: JointType,
141+
#[serde(default)]
142+
pub origin: Pose,
143+
pub parent: LinkName,
144+
pub child: LinkName,
145+
#[serde(default)]
146+
pub axis: Axis,
147+
#[serde(default)]
148+
pub limit: JointLimit,
149+
}
150+
151+
/// Top level struct to access urdf.
152+
#[derive(Debug, Deserialize, Clone)]
153+
pub struct Robot {
154+
#[serde(default)]
155+
pub name: String,
156+
157+
#[serde(rename = "link", default)]
158+
pub links: Vec<Link>,
159+
160+
#[serde(rename = "joint", default)]
161+
pub joints: Vec<Joint>,
162+
163+
#[serde(rename = "material", default)]
164+
pub materials: Vec<Material>,
165+
}

src/funcs.rs renamed to src/sdf/funcs.rs

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
use crate::deserialize::*;
1+
use crate::sdf::deserialize::*;
22
use crate::errors::*;
33

44
use std::path::Path;
@@ -32,7 +32,7 @@ fn sort_link_joint(string: &str) -> Result<String> {
3232
/// # Examples
3333
///
3434
/// ```
35-
/// let urdf_robo = urdf_rs::read_file("sample.urdf").unwrap();
35+
/// let urdf_robo = urdf_rs::sdf::read_file("samples/sample.urdf").unwrap();
3636
/// let links = urdf_robo.links;
3737
/// println!("{:?}", links[0].visual[0].origin.xyz);
3838
/// ```
@@ -88,7 +88,7 @@ pub fn read_file<P: AsRef<Path>>(path: P) -> Result<Robot> {
8888
/// </joint>
8989
/// </robot>
9090
/// "##;
91-
/// let urdf_robo = urdf_rs::read_from_string(s).unwrap();
91+
/// let urdf_robo = urdf_rs::sdf::read_from_string(s).unwrap();
9292
/// println!("{:?}", urdf_robo.links[0].visual[0].origin.xyz);
9393
/// ```
9494

src/sdf/mod.rs

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
mod deserialize;
2+
pub use deserialize::*;
3+
4+
mod funcs;
5+
pub use funcs::*;
6+
7+
pub use crate::errors::*;
8+
pub type SdfError = UrdfError;

0 commit comments

Comments
 (0)