robotics_signals/geometry/
mod.rs1use crate::standard::Header;
2use cdds_derive::Topic;
3use cyclonedds_rs::*;
4use serde_derive::{Deserialize, Serialize};
5
6#[repr(C)]
7#[derive(Serialize, Deserialize)]
8pub struct Vector3 {
9 pub x: f64,
10 pub y: f64,
11 pub z: f64,
12}
13
14#[repr(C)]
15#[derive(Serialize, Deserialize)]
16pub struct Acceleration {
17 pub linear: Vector3,
18 pub angular: Vector3,
19}
20
21#[repr(C)]
22#[derive(Serialize, Deserialize, Topic)]
23pub struct AccelerationStamped {
24 pub header: Header,
25 pub accel: Acceleration,
26}
27
28#[repr(C)]
29#[derive(Serialize, Deserialize)]
30pub struct AccelerationWithCovariance {
31 pub accel: Acceleration,
32 pub covariance: [[f32; 6]; 6],
33}
34
35#[repr(C)]
36#[derive(Serialize, Deserialize, Topic)]
37pub struct AccelerationWithCovarianceStamped {
38 pub header: Header,
39 pub accel: AccelerationWithCovariance,
40}
41
42#[repr(C)]
49#[derive(Serialize, Deserialize)]
50pub struct Inertia {
51 pub mass: f64,
52 pub centre_of_mass: Vector3,
53 pub ixx: f64,
54 pub ixy: f64,
55 pub ixz: f64,
56 pub iyy: f64,
57 pub iyz: f64,
58 pub izz: f64,
59}
60
61#[repr(C)]
62#[derive(Serialize, Deserialize, Topic)]
63pub struct InertiaStamped {
64 header: Header,
65 inertia: Inertia,
66}
67
68#[repr(C)]
69#[derive(Serialize, Deserialize)]
70pub struct Point {
71 pub x: f64,
72 pub y: f64,
73 pub z: f64,
74}
75
76#[repr(C)]
77#[derive(Serialize, Deserialize)]
78pub struct Point32 {
79 pub x: f32,
80 pub y: f32,
81 pub z: f32,
82}
83
84#[repr(C)]
85#[derive(Serialize, Deserialize, Topic)]
86pub struct PointStamped {
87 pub header: Header,
88 pub point: Point,
89}
90
91#[repr(C)]
93#[derive(Serialize, Deserialize)]
94pub struct Polygon {
95 pub points: Vec<Point32>,
96}
97
98#[repr(C)]
99#[derive(Serialize, Deserialize, Topic)]
100pub struct PolygonStamped {
101 pub header: Header,
102 pub polygon: Polygon,
103}
104
105#[repr(C)]
106#[derive(Serialize, Deserialize)]
107pub struct Quarternion {
108 pub x: f64,
109 pub y: f64,
110 pub z: f64,
111 pub w: f64,
112}
113
114#[repr(C)]
115#[derive(Serialize, Deserialize, Topic)]
116pub struct QuarternionStamped {
117 pub header: Header,
118 pub quaternion: Quarternion,
119}
120
121#[repr(C)]
123#[derive(Serialize, Deserialize)]
124pub struct Pose {
125 pub position: Point,
126 pub orientation: Quarternion,
127}
128
129#[repr(C)]
131#[derive(Serialize, Deserialize)]
132pub struct PoseWithCovariance {
133 pub pose: Pose,
134
135 pub covariance: [[f64; 6]; 6],
140}
141
142#[repr(C)]
143#[derive(Serialize, Deserialize)]
144pub struct PoseStamped {
145 pub header: Header,
146 pub pose: Pose,
147}
148
149#[repr(C)]
150#[derive(Serialize, Deserialize, Topic)]
151pub struct PoseWithCovarianceStamped {
152 pub header: Header,
153 pub pose: Pose,
154
155 pub covariance: [[f64; 6]; 6],
160}
161
162#[repr(C)]
164#[derive(Serialize, Deserialize)]
165pub struct Transform {
166 pub translation: Vector3,
167 pub rotation: Quarternion,
168}
169
170#[repr(C)]
171#[derive(Serialize, Deserialize, Topic)]
172pub struct TransformStamped {
173 pub header: Header,
174 pub child_frame_id: String,
175 pub transform: Transform,
176}
177
178#[repr(C)]
179#[derive(Serialize, Deserialize)]
180pub struct Twist {
181 pub linear: Vector3,
182 pub angular: Vector3,
183}
184
185#[repr(C)]
186#[derive(Serialize, Deserialize, Topic)]
187pub struct TwistStamped {
188 pub header: Header,
189 pub twist: Twist,
190}
191
192#[repr(C)]
194#[derive(Serialize, Deserialize)]
195pub struct TwistWithCovariance {
196 pub twist: Twist,
197 pub covariance: [[f32; 6]; 6],
202}
203
204#[repr(C)]
205#[derive(Serialize, Deserialize, Topic)]
206pub struct TwistWithCovarianceStamped {
207 pub header: Header,
208 pub twist: TwistWithCovariance,
209}
210#[repr(C)]
213#[derive(Serialize, Deserialize)]
214pub struct Wrench {
215 pub force: Vector3,
216 pub torque: Vector3,
217}
218
219#[repr(C)]
220#[derive(Serialize, Deserialize, Topic)]
221pub struct WrenchStamped {
222 pub header: Header,
223 pub wrench: Wrench,
224}