-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgroup___d_y_n_a_m_i_c_s.html
616 lines (595 loc) · 32.1 KB
/
group___d_y_n_a_m_i_c_s.html
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
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>lebai-motion-control: dynamics</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="search/search.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="search/searchdata.js"></script>
<script type="text/javascript" src="search/search.js"></script>
<script type="text/javascript">
$(document).ready(function() { init_search(); });
</script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectlogo"><img alt="Logo" src="logo.png"/></td>
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">lebai-motion-control
 <span id="projectnumber">3.1.6</span>
</div>
<div id="projectbrief">lebai motion control C interface</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<script type="text/javascript">
var searchBox = new SearchBox("searchBox", "search",false,'Search');
</script>
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main Page</span></a></li>
<li><a href="pages.html"><span>Related Pages</span></a></li>
<li class="current"><a href="modules.html"><span>Modules</span></a></li>
<li><a href="annotated.html"><span>Data Structures</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
<li>
<div id="MSearchBox" class="MSearchBoxInactive">
<span class="left">
<img id="MSearchSelect" src="search/mag_sel.png"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
alt=""/>
<input type="text" id="MSearchField" value="Search" accesskey="S"
onfocus="searchBox.OnSearchFieldFocus(true)"
onblur="searchBox.OnSearchFieldFocus(false)"
onkeyup="searchBox.OnSearchFieldChange(event)"/>
</span><span class="right">
<a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
</span>
</div>
</li>
</ul>
</div>
</div><!-- top -->
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
onkeydown="return searchBox.OnSearchSelectKey(event)">
</div>
<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="javascript:void(0)" frameborder="0"
name="MSearchResults" id="MSearchResults">
</iframe>
</div>
<div class="header">
<div class="summary">
<a href="#func-members">Functions</a> </div>
<div class="headertitle">
<div class="title">dynamics</div> </div>
</div><!--header-->
<div class="contents">
<p>Dynamics module.
<a href="#details">More...</a></p>
<table class="memberdecls">
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="func-members"></a>
Functions</h2></td></tr>
<tr class="memitem:ga73d106dcee335c5b8fb3ac65867d1ce0"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga73d106dcee335c5b8fb3ac65867d1ce0">lmc_dyn_id</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state, double *const torque)</td></tr>
<tr class="memdesc:ga73d106dcee335c5b8fb3ac65867d1ce0"><td class="mdescLeft"> </td><td class="mdescRight">Compute inverse dynamic of robot: given the joint position, velocity and acceleration, compute the joint torque. <a href="#ga73d106dcee335c5b8fb3ac65867d1ce0">More...</a><br /></td></tr>
<tr class="separator:ga73d106dcee335c5b8fb3ac65867d1ce0"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga8eeb6caacf2af152ea97a17fc66f3d88"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga8eeb6caacf2af152ea97a17fc66f3d88">lmc_dyn_update_tcp_force_direct_estimation</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state, double const *const torque, <a class="el" href="group___m_a_t_h.html#ga1dd90baeb816dc67ba461608a660e5c1">lmc_wrench_t</a> *const f)</td></tr>
<tr class="memdesc:ga8eeb6caacf2af152ea97a17fc66f3d88"><td class="mdescLeft"> </td><td class="mdescRight">Core update of direct dynamic equation based external tcp force estimatation algorithm: given the joint position, velocity and acceleration and current feedback torque on joint, try to estimate the external tcp force. <a href="#ga8eeb6caacf2af152ea97a17fc66f3d88">More...</a><br /></td></tr>
<tr class="separator:ga8eeb6caacf2af152ea97a17fc66f3d88"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga4e10c5998af6851eedf293ebea2bc364"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga4e10c5998af6851eedf293ebea2bc364">lmc_dyn_update_tcp_force_momentum_observer_estimation</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, double cycle_time, <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state, double const *const torque, <a class="el" href="group___m_a_t_h.html#ga1dd90baeb816dc67ba461608a660e5c1">lmc_wrench_t</a> *const f)</td></tr>
<tr class="memdesc:ga4e10c5998af6851eedf293ebea2bc364"><td class="mdescLeft"> </td><td class="mdescRight">Core update of momentum observer based external tcp force estimatation algorithm: given the joint position, velocity and current feedback torque on joint, try to estimate the external tcp force. <a href="#ga4e10c5998af6851eedf293ebea2bc364">More...</a><br /></td></tr>
<tr class="separator:ga4e10c5998af6851eedf293ebea2bc364"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:gafdeb89bb7eefe7846969a753f7639057"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#gafdeb89bb7eefe7846969a753f7639057">lmc_dyn_init_tcp_force_momentum_observer_estimation</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state)</td></tr>
<tr class="memdesc:gafdeb89bb7eefe7846969a753f7639057"><td class="mdescLeft"> </td><td class="mdescRight">Init momentum observer estimation. <a href="#gafdeb89bb7eefe7846969a753f7639057">More...</a><br /></td></tr>
<tr class="separator:gafdeb89bb7eefe7846969a753f7639057"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:gae20d8034e9330e65973a5c3dc66aa083"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#gae20d8034e9330e65973a5c3dc66aa083">lmc_dyn_estimate_payload_with_twice_strategy</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, <a class="el" href="lmc__joint_8h.html#a7e25619eb53d8ed936979ebffcdb325a">lmc_all_sampled_joint_state_t</a> const *const all_sampled_data, double *const mass, <a class="el" href="group___m_a_t_h.html#ga8374faadca414a54856e2bc3e33ff9e4">lmc_translation_t</a> *const com)</td></tr>
<tr class="memdesc:gae20d8034e9330e65973a5c3dc66aa083"><td class="mdescLeft"> </td><td class="mdescRight">Estimate payload parameter. <a href="#gae20d8034e9330e65973a5c3dc66aa083">More...</a><br /></td></tr>
<tr class="separator:gae20d8034e9330e65973a5c3dc66aa083"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga7f1f377bbbecdfe6af85322cb224c30d"><td class="memItemLeft" align="right" valign="top">*int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga7f1f377bbbecdfe6af85322cb224c30d">lmc_dyn_gravity_compensate</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state,*double *const torque)</td></tr>
<tr class="memdesc:ga7f1f377bbbecdfe6af85322cb224c30d"><td class="mdescLeft"> </td><td class="mdescRight">Compute gravity compensation for robot, can be used for teaching. <a href="#ga7f1f377bbbecdfe6af85322cb224c30d">More...</a><br /></td></tr>
<tr class="separator:ga7f1f377bbbecdfe6af85322cb224c30d"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga7e56720049f631176b27152af3937f54"><td class="memItemLeft" align="right" valign="top">**int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga7e56720049f631176b27152af3937f54">lmc_dyn_computed_torque_control</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model,*<a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const joint_state, <a class="el" href="lmc__joint_8h.html#a997f3c13282a8cf93542e60677852155">lmc_joint_cmd_t</a> const *const joint_cmd,*double *const torque, double *const inertia)</td></tr>
<tr class="memdesc:ga7e56720049f631176b27152af3937f54"><td class="mdescLeft"> </td><td class="mdescRight">Computed torque control algorithm. <a href="#ga7e56720049f631176b27152af3937f54">More...</a><br /></td></tr>
<tr class="separator:ga7e56720049f631176b27152af3937f54"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga1f7d7d0feb0da58d0ff49b73ab6327b0"><td class="memItemLeft" align="right" valign="top">**int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga1f7d7d0feb0da58d0ff49b73ab6327b0">lmc_dyn_set_computed_torque_control_param</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const robot_model, const double *kp, const double *kv)</td></tr>
<tr class="memdesc:ga1f7d7d0feb0da58d0ff49b73ab6327b0"><td class="mdescLeft"> </td><td class="mdescRight">Set computed torque control parameters. <a href="#ga1f7d7d0feb0da58d0ff49b73ab6327b0">More...</a><br /></td></tr>
<tr class="separator:ga1f7d7d0feb0da58d0ff49b73ab6327b0"><td class="memSeparator" colspan="2"> </td></tr>
<tr class="memitem:ga879807fe84f0182f32bea701de433936"><td class="memItemLeft" align="right" valign="top">*int </td><td class="memItemRight" valign="bottom"><a class="el" href="group___d_y_n_a_m_i_c_s.html#ga879807fe84f0182f32bea701de433936">lmc_dyn_set_gravity</a> (<a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> const *const robot_model, <a class="el" href="group___m_a_t_h.html#ga8374faadca414a54856e2bc3e33ff9e4">lmc_translation_t</a> const *const gravity)</td></tr>
<tr class="memdesc:ga879807fe84f0182f32bea701de433936"><td class="mdescLeft"> </td><td class="mdescRight">Set gravity vector, will affect all the dynamic algorithms. <a href="#ga879807fe84f0182f32bea701de433936">More...</a><br /></td></tr>
<tr class="separator:ga879807fe84f0182f32bea701de433936"><td class="memSeparator" colspan="2"> </td></tr>
</table>
<a name="details" id="details"></a><h2 class="groupheader">Detailed Description</h2>
<p>Dynamics module. </p>
<h2 class="groupheader">Function Documentation</h2>
<a class="anchor" id="ga7e56720049f631176b27152af3937f54"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">* * int lmc_dyn_computed_torque_control </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">*<a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a997f3c13282a8cf93542e60677852155">lmc_joint_cmd_t</a> const *const </td>
<td class="paramname"><em>joint_cmd</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">*double *const </td>
<td class="paramname"><em>torque</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double *const </td>
<td class="paramname"><em>inertia</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Computed torque control algorithm. </p>
<p>/**</p><ul>
<li>* <dl class="section note"><dt>Note</dt><dd></dd></dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">joint_cmd</td><td>Joint command data input for compute.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[out]</td><td class="paramname">torque</td><td>The torque computing result.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[out]</td><td class="paramname">inertia</td><td>The computed matrix principal diagonal inertia, mostly represent joint inertia state. </td></tr>
</table>
</dd>
</dl>
</li>
</ul>
</div>
</div>
<a class="anchor" id="gae20d8034e9330e65973a5c3dc66aa083"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">int lmc_dyn_estimate_payload_with_twice_strategy </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a7e25619eb53d8ed936979ebffcdb325a">lmc_all_sampled_joint_state_t</a> const *const </td>
<td class="paramname"><em>all_sampled_data</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double *const </td>
<td class="paramname"><em>mass</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="group___m_a_t_h.html#ga8374faadca414a54856e2bc3e33ff9e4">lmc_translation_t</a> *const </td>
<td class="paramname"><em>com</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Estimate payload parameter. </p>
<dl class="section note"><dt>Note</dt><dd>Maximun 1000 sample points. </dd></dl>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">all_sampled_data</td><td>All sampled data. For joint torques, we get the delta torques of two measurements. Only one joint can move simultaneously. </td></tr>
<tr><td class="paramdir">[out]</td><td class="paramname">mass</td><td>computed mass. </td></tr>
<tr><td class="paramdir">[out]</td><td class="paramname">com</td><td>computed center of mass. </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
<a class="anchor" id="ga7f1f377bbbecdfe6af85322cb224c30d"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">* int lmc_dyn_gravity_compensate </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">*double *const </td>
<td class="paramname"><em>torque</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Compute gravity compensation for robot, can be used for teaching. </p>
<p>/**</p><ul>
<li>* <dl class="section note"><dt>Note</dt><dd></dd></dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[out]</td><td class="paramname">torque</td><td>The computed result in array form. </td></tr>
</table>
</dd>
</dl>
</li>
</ul>
</div>
</div>
<a class="anchor" id="ga73d106dcee335c5b8fb3ac65867d1ce0"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">int lmc_dyn_id </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double *const </td>
<td class="paramname"><em>torque</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Compute inverse dynamic of robot: given the joint position, velocity and acceleration, compute the joint torque. </p>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute. </td></tr>
<tr><td class="paramdir">[out]</td><td class="paramname">torque</td><td>The computed result in array form. </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
<a class="anchor" id="gafdeb89bb7eefe7846969a753f7639057"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">int lmc_dyn_init_tcp_force_momentum_observer_estimation </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Init momentum observer estimation. </p>
<dl class="section note"><dt>Note</dt><dd>This is a momentum observer based algorithm. this method must be called continously in every cycle. </dd></dl>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute, only position and velocity will be used. </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
<a class="anchor" id="ga1f7d7d0feb0da58d0ff49b73ab6327b0"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">* * int lmc_dyn_set_computed_torque_control_param </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">const double * </td>
<td class="paramname"><em>kp</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">const double * </td>
<td class="paramname"><em>kv</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Set computed torque control parameters. </p>
<p>/**</p><ul>
<li>* <dl class="section note"><dt>Note</dt><dd>In old lebai_kdl, we set these parameter in init function. Now we use this standalone api.</dd></dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data structure for setting.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">kp</td><td>kp array data.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">kv</td><td>kv array data.</td></tr>
</table>
</dd>
</dl>
</li>
<li><dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</li>
</ul>
</div>
</div>
<a class="anchor" id="ga879807fe84f0182f32bea701de433936"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">* int lmc_dyn_set_gravity </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> const *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="group___m_a_t_h.html#ga8374faadca414a54856e2bc3e33ff9e4">lmc_translation_t</a> const *const </td>
<td class="paramname"><em>gravity</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Set gravity vector, will affect all the dynamic algorithms. </p>
<dl class="section note"><dt>Note</dt><dd></dd></dl>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data structure for setting. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">gravity</td><td>gravity vector data </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
<a class="anchor" id="ga8eeb6caacf2af152ea97a17fc66f3d88"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">int lmc_dyn_update_tcp_force_direct_estimation </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double const *const </td>
<td class="paramname"><em>torque</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="group___m_a_t_h.html#ga1dd90baeb816dc67ba461608a660e5c1">lmc_wrench_t</a> *const </td>
<td class="paramname"><em>f</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Core update of direct dynamic equation based external tcp force estimatation algorithm: given the joint position, velocity and acceleration and current feedback torque on joint, try to estimate the external tcp force. </p>
<dl class="section note"><dt>Note</dt><dd>This is a direct method using dynamic equation to estimate tcp force. Set vel and acc to zero in <a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> in case vel and acc data is not stable due to differential compute. </dd></dl>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">torque</td><td>The actual joint torque in array form. </td></tr>
<tr><td class="paramdir">[out]</td><td class="paramname">f</td><td>The external tcp force. </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
<a class="anchor" id="ga4e10c5998af6851eedf293ebea2bc364"></a>
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">int lmc_dyn_update_tcp_force_momentum_observer_estimation </td>
<td>(</td>
<td class="paramtype"><a class="el" href="group___r_o_b_o_t___m_o_d_e_l.html#ga88801e600508c29bfd792993c252af02">lmc_robot_model_t</a> *const </td>
<td class="paramname"><em>robot_model</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double </td>
<td class="paramname"><em>cycle_time</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="lmc__joint_8h.html#a834eed68f0b2dad17a4f52a885e5e1d5">lmc_joint_state_t</a> const *const </td>
<td class="paramname"><em>joint_state</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">double const *const </td>
<td class="paramname"><em>torque</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="group___m_a_t_h.html#ga1dd90baeb816dc67ba461608a660e5c1">lmc_wrench_t</a> *const </td>
<td class="paramname"><em>f</em> </td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td>
</tr>
</table>
</div><div class="memdoc">
<p>Core update of momentum observer based external tcp force estimatation algorithm: given the joint position, velocity and current feedback torque on joint, try to estimate the external tcp force. </p>
<dl class="section note"><dt>Note</dt><dd>This is a momentum observer based algorithm. this method must be called continously in every cycle. </dd></dl>
<dl class="params"><dt>Parameters</dt><dd>
<table class="params">
<tr><td class="paramdir">[in]</td><td class="paramname">robot_model</td><td>Robot model data for dynamic computing. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">cycle_time</td><td>loop cycle time. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">joint_state</td><td>Joint state data input for compute, only position and velocity will be used. </td></tr>
<tr><td class="paramdir">[in]</td><td class="paramname">torque</td><td>The actual joint torque in array form. </td></tr>
<tr><td class="paramdir">[out]</td><td class="paramname">f</td><td>The external tcp force. </td></tr>
</table>
</dd>
</dl>
<dl class="section return"><dt>Returns</dt><dd>Return 0 on success, otherwise failure. </dd></dl>
</div>
</div>
</div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by  <a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>