pitasc_library - scripts/geometry.xml
Model definitions
line 67: script_temp_frame
line 119: script_set_frame
line 163: script_set_frame_rotvec
line 173: script_temp_frame_from_force
line 208: script_sinus_frame
File contents
1<?xml version="1.0" encoding="UTF-8"?>
2
3<pitasc>
4
5 <models>
6
7 <!-- Kinematic Graph -->
8
9 <type id="script_kinematic_graph" prototype="script">
10 <meta>
11 <member id="description">Prototype for kinematic graph scripts</member>
12 <member id="categories">internal</member>
13 </meta>
14 <data>
15 <type id="on_start" prototype="bool_parameter">
16 <meta>
17 <member id="description">Execute the script before or after the skill.</member>
18 <member id="visibility">basic</member>
19 </meta>
20 <data>True</data>
21 </type>
22
23 <type id="tf_broadcast" prototype="bool_parameter">
24 <meta>
25 <member id="description">Broadcast the frame to TF?</member>
26 <member id="visibility">basic</member>
27 </meta>
28 <data>False</data>
29 </type>
30
31 <reference prototype="kinematic_graph" reference_id="configuration.kinematic_graph"/>
32 <member id="kinematic_graph.meta.visibility">hidden</member>
33 </data>
34 </type>
35
36 <type id="script_copy_frame" prototype="script_kinematic_graph">
37 <meta>
38 <member id="description">Copies a frame.</member>
39 <member id="categories">frames</member>
40 <member id="implementation">
41 </member>
42 </meta>
43 <data>
44 <type id="frame" prototype="string_parameter">
45 <meta>
46 <member id="description">Name of the frame to be created</member>
47 <member id="visibility">required</member>
48 </meta>
49 </type>
50
51 <type id="source" prototype="string_parameter">
52 <meta>
53 <member id="description">Name of the frame to be copied</member>
54 <member id="visibility">required</member>
55 </meta>
56 </type>
57
58 <type id="parent" prototype="string_parameter">
59 <meta>
60 <member id="description">Name of the parent frame to of 'frame'</member>
61 <member id="visibility">required</member>
62 </meta>
63 </type>
64 </data>
65 </type>
66
67 <type id="script_temp_frame" prototype="script_kinematic_graph">
68 <meta>
69 <member id="description">Creates a temporary frame that lives as long as the parent skill is active.</member>
70 <member id="categories">frames</member>
71 <member id="implementation">
72 <clone prototype="orocos">
73 <member id="package">cppitasc_kinematics</member>
74 <member id="component">ScriptTempFrame</member>
75 </clone>
76 </member>
77 </meta>
78 <data>
79 <type id="frame" prototype="string_parameter">
80 <meta>
81 <member id="description">Name of the frame to be created</member>
82 <member id="visibility">required</member>
83 </meta>
84 </type>
85
86 <type id="source" prototype="string_parameter">
87 <meta>
88 <member id="description">Name of the frame to be copied</member>
89 <member id="visibility">required</member>
90 </meta>
91 </type>
92
93 <type id="parent" prototype="string_parameter">
94 <meta>
95 <member id="description">Name of the parent frame to of 'frame'</member>
96 <member id="visibility">required</member>
97 </meta>
98 </type>
99 </data>
100 </type>
101
102 <type id="script_remove_frame" prototype="script_kinematic_graph">
103 <meta>
104 <member id="description">Removes a frame.</member>
105 <member id="categories">frames</member>
106 <member id="implementation">
107 </member>
108 </meta>
109 <data>
110 <type id="frame" prototype="string_parameter">
111 <meta>
112 <member id="description">Name of the frame to be removed.</member>
113 <member id="visibility">required</member>
114 </meta>
115 </type>
116 </data>
117 </type>
118
119 <type id="script_set_frame" prototype="script_kinematic_graph">
120 <meta>
121 <member id="description">Sets a new frame.</member>
122 <member id="categories">frames</member>
123 <member id="implementation">
124 <clone prototype="orocos">
125 <member id="package">cppitasc_kinematics</member>
126 <member id="component">ScriptSetFrame</member>
127 </clone>
128 </member>
129 </meta>
130 <data>
131 <type id="frame" prototype="string_parameter">
132 <meta>
133 <member id="description">Name of the frame to be set or created</member>
134 <member id="visibility">required</member>
135 </meta>
136 </type>
137
138 <type id="parent" prototype="string_parameter">
139 <meta>
140 <member id="description">Name of the parent frame to of 'frame'</member>
141 <member id="visibility">required</member>
142 </meta>
143 </type>
144
145 <type id="pose" prototype="float_csv">
146 <meta>
147 <member id="description">Pose of the new frame relative to 'parent'</member>
148 <member id="visibility">required</member>
149 </meta>
150 </type>
151 <type id="pose_type" prototype="string_parameter">
152 <meta>
153 <member id="description">Specifies how the rotation part of pose is given.</member>
154 <clone prototype="restrictions">
155 <clone prototype="enum">rpy, rot_vec</clone>
156 </clone>
157 </meta>
158 <data>rpy</data>
159 </type>
160 </data>
161 </type>
162
163 <type id="script_set_frame_rotvec" prototype="script_set_frame">
164 <meta>
165 <member id="description">Sets a new frame (pose with rotation vector).</member>
166 </meta>
167 <data>
168 <member id="pose_type">rot_vec</member>
169 </data>
170 </type>
171
172
173 <type id="script_temp_frame_from_force" prototype="script_temp_frame">
174 <meta>
175 <member id="description">Creates a temporary frame from the current force measurements.
176
177 The z axis points in the opposite direction of the measured force vector (the usual definition for force control with pitasc).
178 The frame's position and direction will be updated as long as the script is active.
179
180 Includes possibility to filter the input with a first order low pass.
181 </member>
182 <member id="categories">frames</member>
183 <member id="implementation">
184 <clone prototype="orocos">
185 <member id="package">cppitasc_kinematics</member>
186 <member id="component">ScriptTempFrameFromForce</member>
187 </clone>
188 </member>
189 </meta>
190 <data>
191 <reference id="wrench_driver" prototype="data_source" reference_id="robot.components.force_sensor.wrench_driver"/>
192 <member id="wrench_driver.meta.visibility">expert</member>
193
194 <member id="parent" reference_id="robot.base_link"/>
195 <member id="parent.meta.visibility">expert</member>
196
197 <type id="low_pass_filter_gain" prototype="float_parameter">
198 <meta>
199 <member id="description">First order low pass filter gain (exponential filter). Must be in interval [0:1]. 0 means taking only the previous value, 1 means taking only the new value.</member>
200 <member id="visibility">basic</member>
201 </meta>
202 <data>1</data>
203 </type>
204
205 </data>
206 </type>
207
208 <type id="script_sinus_frame" prototype="script_temp_frame">
209 <meta>
210 <member id="description">Creates a temporary frame that lives as long as the parent skill is active. The frame moves in the given coordinate with a sinus</member>
211 <member id="categories">frames</member>
212 <member id="implementation">
213 <clone prototype="orocos">
214 <member id="package">cppitasc_kinematics</member>
215 <member id="component">ScriptSinusFrame</member>
216 </clone>
217 </member>
218 </meta>
219 <data>
220 <type id="coordinate" prototype="string_parameter">
221 <meta>
222 <member id="description">Coordinate that will be updated by a sine.</member>
223 <member id="visibility">required</member>
224 </meta>
225 </type>
226 <type id="amplitude" prototype="float_parameter">
227 <meta>
228 <member id="description">Amplitude of the sine.</member>
229 <member id="visibility">required</member>
230 </meta>
231 </type>
232 <type id="period" prototype="float_parameter">
233 <meta>
234 <member id="description">Period of the sine in [s].</member>
235 <member id="visibility">required</member>
236 </meta>
237 </type>
238 </data>
239 </type>
240
241 </models>
242</pitasc>