-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathjoint.proto
199 lines (165 loc) · 6.1 KB
/
joint.proto
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
syntax = "proto3";
import "types.proto";
import "motor.proto";
package mirabuf.joint;
// You can have an Open-Chain robot meaning a single path
// You can have a closed chain mechanism or Four-bar (closed loop)
// Or multiple paths with closed loop like a stewart platform
/**
* Joints
* A way to define the motion between various group connections
*/
message Joints {
Info info = 1; /// name, version, uid
map<string, Joint> joint_definitions = 2; /// Unique Joint Implementations
map<string, JointInstance> joint_instances = 3; /// Instances of the Joint Implementations
repeated RigidGroup rigid_groups = 4; /// Rigidgroups ?
map<string, motor.Motor> motor_definitions = 5; /// Collection of all Motors exported
}
// Describes the joint - Not really sure what to do with this for now - TBD
enum JointMotion {
RIGID = 0;
REVOLUTE = 1;
SLIDER = 2;
CYLINDRICAL= 3;
PINSLOT = 4;
PLANAR = 5;
BALL = 6;
CUSTOM = 7;
}
/**
* Instance of a Joint that has a defined motion and limits.
* Instancing helps with identifiy closed loop systems.
*/
message JointInstance {
// Joint name, ID, version, etc
Info info = 1;
// Is this joint the end effector in the tree ? - might remove this
bool isEndEffector = 2;
// Object that contains the joint - the ID - Part usually
string parent_part = 3;
// Object that is affected by the joint - the ID - Part usually
string child_part= 4;
// Reference to the Joint Definition
string joint_reference = 5;
// Offset from Joint Definition Origin
Vector3 offset = 6;
// Part Instances all contained and affected by this joint directly - tree
GraphContainer parts = 7;
// Reference to the Signals as Drivers - use for signal_map in Assembly Data
string signal_reference = 8;
// Motion Links to other joints - ways to preserve motion between dynamic objects
repeated MotionLink motion_link = 9;
}
/**
* Motion Link Feature
* Enables the restriction on a joint to a certain range of motion as it is relative to another joint
* This is useful for moving parts restricted by belts and gears
*/
message MotionLink {
// The Joint that this is linked to
string joint_instance = 1;
// Ratio of motion between joint 1 and joint 2, we assume this is in mm for linear and deg for rotational
float ratio = 2;
// Reverse the relationship - turn in the same or opposite directions - useful when moving axis arent both the same way.
bool reversed = 3;
}
/**
* A unqiue implementation of a joint motion
* Contains information about motion but not assembly relation
* NOTE: A spring motion is a joint with no driver
*/
message Joint {
/// Joint name, ID, version, etc
Info info = 1;
// Transform relative to the parent
Vector3 origin = 2;
// type of motion described by the joint
JointMotion joint_motion_type = 3;
// At what effort does it come apart at. - leave blank if it doesn't
float break_magnitude = 4;
// The actual motion of the joint
oneof JointMotion {
RotationalJoint rotational = 5; /// ONEOF rotational joint
PrismaticJoint prismatic = 6; /// ONEOF prismatic joint
CustomJoint custom = 7; /// ONEOF custom joint
// todo reserve some spaces here or get rid of the oneof entirely
}
/// Additional information someone can query or store relative to your joint.
UserData user_data = 8;
string motor_reference = 9; /// Motor definition reference to lookup in joints collection
}
/**
* Dynamics specify the mechanical effects on the motion.
*/
message Dynamics {
float damping = 1; /// Damping effect on a given joint motion
float friction = 2; /// Friction effect on a given joint motion
}
/**
* Limits specify the mechanical range of a given joint.
*
* TODO: Add units
*/
message Limits {
float lower = 1; /// Lower Limit corresponds to default displacement
float upper = 2; /// Upper Limit is the joint extent
float velocity = 3; /// Velocity Max in m/s^2 (angular for rotational)
/// Effort is the absolute force a joint can apply for a given instant - ROS has a great article on it http://wiki.ros.org/pr2_controller_manager/safety_limits
float effort = 4;
}
/**
* Safety switch configuration for a given joint.
* Can usefully indicate a bounds issue.
* Inspired by the URDF implementation.
*
* This should really just be created by the controller.
* http://wiki.ros.org/pr2_controller_manager/safety_limits
*/
message Safety {
float lower_limit = 1; /// Lower software limit
float upper_limit = 2; /// Upper Software limit
float k_position = 3; /// Relation between position and velocity limit
float k_velocity = 4; /// Relation between effort and velocity limit
}
/**
* DOF - representing the construction of a joint motion
*/
message DOF {
string name = 1; /// In case you want to name this degree of freedom
Vector3 axis = 2; /// Axis the degree of freedom is pivoting by
Axis pivotDirection = 3; /// Direction the axis vector is offset from - this has an incorrect naming scheme
Dynamics dynamics = 4; /// Dynamic properties of this joint pivot
Limits limits = 5; /// Limits of this freedom
float value = 6; /// Current value of the DOF
}
/**
* CustomJoint is a joint with N degrees of freedom specified.
* There should be input validation to handle max freedom case.
*/
message CustomJoint {
repeated DOF dofs = 1; /// A list of degrees of freedom that the joint can contain
}
/**
* RotationalJoint describes a joint with rotational translation.
* This is the exact same as prismatic for now.
*/
message RotationalJoint {
DOF rotational_freedom = 1;
}
message BallJoint {
DOF yaw = 1;
DOF pitch = 2;
DOF rotation = 3;
}
/**
* Prismatic Joint describes a motion that translates the position in a single axis
*/
message PrismaticJoint {
DOF prismatic_freedom = 1;
}
message RigidGroup {
string name = 1;
// this could be the full path of the occurrence in order to make it easier to assembly them possibly - just parse on the unity side
repeated string occurrences = 2;
}