Skip to content

Commit

Permalink
[doc][ros_bridge][py] Explain more about startImpedance.
Browse files Browse the repository at this point in the history
The added change is a duplicate with the PR in the upstream fkanehiro/hrpsys-base#1120, which assumedly will take awhile to get merged. Once it does then this commit should be reverted to avoid duplicate maintenance effort.
  • Loading branch information
130s committed May 9, 2017
1 parent 2125a56 commit ebe44ff
Showing 1 changed file with 20 additions and 0 deletions.
20 changes: 20 additions & 0 deletions hironx_ros_bridge/src/hironx_ros_bridge/hironx_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -1037,6 +1037,26 @@ def startImpedance(self, arm, **kwargs):
(which you can find by "self.hrpsys_version" command).
For instance, if your hrpsys is 315.10.1, refer to
"startImpedance_315_4" method.
@change: (NOTE: This "change" block is a duplicate with the PR in the
upstream https://github.com/fkanehiro/hrpsys-base/pull/1120.
Once it gets merged this block should be removed to avoid
duplicate maintenance effort.)
From 315.2.0 onward, following arguments are dropped and can
be set by self.seq_svc.setWrenches instead of this method.
See an example at https://github.com/fkanehiro/hrpsys-base/pull/434/files#diff-6204f002204dd9ae80f203901f155fa9R44:
- ref_force[fx, fy, fz] (unit: N) and
ref_moment[tx, ty, tz] (unit: Nm) can be set via
self.seq_svc.setWrenches. For example:
self.seq_svc.setWrenches([0, 0, 0, 0, 0, 0,
fx, fy, fz, tx, ty, tz,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,])
setWrenches takes 6 values per sensor, so the robot in
the example above has 4 sensors where each line represents
a sensor. See this link (https://github.com/fkanehiro/hrpsys-base/pull/434/files) for a concrete example.
'''
if StrictVersion(self.hrpsys_version) < StrictVersion('315.2.0'):
self.startImpedance_315_1(arm, **kwargs)
Expand Down

0 comments on commit ebe44ff

Please sign in to comment.