Public Member Functions | Public Attributes | Static Public Attributes | Static Private Attributes
hironx_ros_bridge.hironx_client.HIRONX Class Reference
Inheritance diagram for hironx_ros_bridge.hironx_client.HIRONX:
Inheritance graph
[legend]

List of all members.

Public Member Functions

def checkEncoders
def clearOfGroup
 Clears the Sequencer's current operation for joint groups.
def flat2Groups
def getJointAnglesOfGroup
def getRTCList
def goInitial
def goOffPose
def hand_width2angles
def HandClose
def HandOpen
def init
def isCalibDone
def isServoOn
def moveHand
def removeForceSensorOffset
def servoOff
def servoOn
def setHandEffort
def setHandJointAngles
def setHandWidth
def setSelfGroups
def startImpedance
def startImpedance_315_1
def startImpedance_315_2
def startImpedance_315_3
def stopImpedance
def stopImpedance_315_1
def stopImpedance_315_2
def stopImpedance_315_3

Public Attributes

 hrpsys_version
 sensors

Static Public Attributes

list Groups
dictionary HandGroups = {'rhand': [2, 3, 4, 5], 'lhand': [6, 7, 8, 9]}
string hrpsys_version = '0.0.0'
int INITPOS_TYPE_EVEN = 0
int INITPOS_TYPE_FACTORY = 1
list OffPose
list RtcList = []
 sc = None
 sc_svc = None

Static Private Attributes

list _InitialPose
list _InitialPose_Factory
tuple _MSG_IMPEDANCE_CALL_DONE

Detailed Description

@see: <a href = "https://github.com/fkanehiro/hrpsys-base/blob/master/" +
                "python/hrpsys_config.py">HrpsysConfigurator</a>

This class holds methods that are specific to Kawada Industries' dual-arm
robot called Hiro.

For the API doc for the derived methods, please see the parent
class via the link above; nicely formatted api doc web page
isn't available yet (discussed in
https://github.com/fkanehiro/hrpsys-base/issues/268).

Definition at line 261 of file hironx_client.py.


Member Function Documentation

def hironx_ros_bridge.hironx_client.HIRONX.checkEncoders (   self,
  jname = 'all',
  option = '' 
)
Run the encoder checking sequence for specified joints,
run goActual to adjust the direction values, and then turn servos on.

@type jname: str
@param jname: The value 'all' works iteratively for all servos.
@type option: str
@param option: Possible values are follows (w/o double quote):\
        "-overwrite": Overwrite calibration value.

Definition at line 833 of file hironx_client.py.

Clears the Sequencer's current operation for joint groups.

Since:
315.5.0

Definition at line 1122 of file hironx_client.py.

@type flatList: [int]
@param flatList: single dimension list, with its length depends on
         'Groups' variable defined within this class. Excessive
         elements will be dropped (see example below in @return)

         eg. If the number of joints of the robot is 15,
             len(flatList) should be 15.
@rtype: [[]]
@return: 2-dimensional list that has the same format with
 'Groups' variable.

 eg.
 ipython> flatlist = [0, 10, 20, 30, 40, 50, 60, 70, 80, 90,
                      100, 110, 120, 130, 140, 150]
 ipython> robot.flat2Groups(flatlist)
 [[0], [10, 20],
  [30, 40, 50, 60, 70, 80],
  [90, 100, 110, 120, 130, 140]]

Definition at line 641 of file hironx_client.py.

Definition at line 1099 of file hironx_client.py.

@see: HrpsysConfigurator.getRTCList

@rtype [[str]]
@rerutrn List of available components. Each element consists of a list
 of abbreviated and full names of the component.

Definition at line 437 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.goInitial (   self,
  tm = 7,
  wait = True,
  init_pose_type = 0 
)
Move arms to the predefined (as member variable) "initialized" pose.

@type tm: float
@param tm: Second to complete.
@type wait: bool
@param wait: If true, other command to the robot's joints wait until
     this command returns (done by running
     SequencePlayer.waitInterpolationOfGroup).
@type init_pose_type: int
@param init_pose_type: 0: default init pose (specified as _InitialPose)
               1: factory init pose (specified as
                  _InitialPose_Factory)

Definition at line 402 of file hironx_client.py.

Move arms to the predefined (as member variable) pose where robot can
be safely turned off.

@type tm: float
@param tm: Second to complete.

Definition at line 387 of file hironx_client.py.

TODO: Needs documented what this method does.

@type width: float
@return: None if the given width is invalid.

Definition at line 559 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.HandClose (   self,
  hand = None,
  effort = None 
)
Close 2-finger hand, by internally calling self.setHandWidth
setting 0 width.

@type hand: str
@param hand: Name of the hand joint group. In the default
     setting of HIRONX, hand joint groups are defined
     in member 'HandGroups' where 'lhand' and 'rhand'
     are added.
@type effort: int

Definition at line 487 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.HandOpen (   self,
  hand = None,
  effort = None 
)
Set the stretch between two fingers of the specified hand as
hardcoded value (100mm), by internally calling self.setHandWidth.

@type hand: str
@param hand: Name of the hand joint group. In the default
     setting of HIRONX, hand joint groups are defined
     in member 'HandGroups' where 'lhand' and 'rhand'
     are added.
@type effort: int

Definition at line 473 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.init (   self,
  robotname = "HiroNX(Robot)0",
  url = "" 
)
Calls init from its superclass, which tries to connect RTCManager,
looks for ModelLoader, and starts necessary RTC components. Also runs
config, logger.
Also internally calls setSelfGroups().

@type robotname: str
@type url: str

Definition at line 322 of file hironx_client.py.

Check whether joints have been calibrated.
@rtype bool

Definition at line 595 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.isServoOn (   self,
  jname = 'any' 
)
Check whether servo control has been turned on. Check is done by
HIRONX.getActualState().servoState.
@type jname: str
@param jname: Name of a link (that can be obtained by "hiro.Groups"
      as lists of groups).

      Reserved values:
      - any: This command will check all servos available.
      - all: Same as 'any'.
@rtype bool
@return: If jname is specified either 'any' or 'all', return False
 if the control of any of servos isn't available.

Definition at line 609 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.moveHand (   self,
  hand,
  av,
  tm = 1 
)
Negate the angle value for {2, 3, 6, 7}th element in av.

@type hand: str
@param hand: Specifies hand. (TODO: List the possible values. Should be
     listed in setHandJointAngles so just copy from its doc.)
@type av: [int]
@param av: angle of each joint of the specified arm
  (TODO: need verified. Also what's the length of the list?)
@param tm: Time in second to complete the work.

Definition at line 543 of file hironx_client.py.

Definition at line 1094 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.servoOff (   self,
  jname = 'all',
  wait = True 
)
@type jname: str
@param jname: The value 'all' works iteratively for all servos.
@type wait: bool
@rtype: int
@return: 1 = all arm servo off. 2 = all servo on arms and hands off.
-1 = Something wrong happened.

Definition at line 785 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.servoOn (   self,
  jname = 'all',
  destroy = 1,
  tm = 3 
)
Turn on servo motors at joint specified.
Joints need to be calibrated (otherwise error returns).

*Troubleshooting*
When this method does not seem to function as expected, try the
following first before you report to the developer's community:

- Manually move the arms to the safe pose where arms do not obstruct
  to anything and they can move back to the initial pose by goInitial.
  Then run the command again.
- Make sure the emergency switch is toggled back.
- Try running goActual() then servoOn().

If none of the above did not solve your issue, please report with:
- The result of this command (%ROSDISTRO% is "indigo" as of May 2017):

    Ubuntu$ rosversion hironx_ros_bridge
    Ubuntu$ dpkg -p ros-%ROSDISTRO%-hironx-ros-bridge

@type jname: str
@param jname: The value 'all' works iteratively for all servos.
@param destroy: Not used.
@type tm: float
@param tm: Second to complete.
@rtype: int
@return: 1 or -1 indicating success or failure, respectively.

Definition at line 671 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.setHandEffort (   self,
  effort = 100 
)
Set maximum torque for all existing hand components.
@type effort: int

Definition at line 514 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.setHandJointAngles (   self,
  hand,
  angles,
  tm = 1 
)
@type hand: str
@param hand: Name of the hand joint group. In the default
     setting of HIRONX, hand joint groups are defined
     in member 'HandGroups' where 'lhand' and 'rhand'
     are added.
@type angles: OpenHRP::ServoControllerService::dSequence.
@param angles: List of (TODO: document). Elements are in degree.
@param tm: Time to complete the task.

Definition at line 501 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.setHandWidth (   self,
  hand,
  width,
  tm = 1,
  effort = None 
)
@type hand: str
@param hand: Name of the hand joint group. In the default
     setting of HIRONX, hand joint groups are defined
     in member 'HandGroups' where 'lhand' and 'rhand'
     are added.
@param width: Max=100.
@param tm: Time to complete the move.
@type effort: int
@param effort: Passed to self.setHandEffort if set. Not set by default.

Definition at line 523 of file hironx_client.py.

Set to the hrpsys.SequencePlayer the groups of links and joints that
are statically defined as member variables (Groups) within this class.

That said, override Groups variable if you prefer link and joint
groups set differently.

Definition at line 579 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.startImpedance (   self,
  arm,
  kwargs 
)
Enable the ImpedanceController RT component.
This method internally calls startImpedance-*, hrpsys version-specific
method.

@requires: ImpedanceController RTC to be activated on the robot's
   controller.
@param arm: Name of the kinematic group (i.e. self.Groups[n][0]).
@param kwargs: This varies depending on the version of hrpsys your
       robot's controller runs on
       (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.

Definition at line 1042 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.startImpedance_315_1 (   self,
  arm,
  M_p = 100.0,
  D_p = 100.0,
  K_p = 100.0,
  M_r = 100.0,
  D_r = 2000.0,
  K_r = 2000.0,
  ref_force = [0,
  force_gain = [1,
  ref_moment = [0,
  moment_gain = [0,
  sr_gain = 1.0,
  avoid_gain = 0.0,
  reference_gain = 0.0,
  manipulability_limit = 0.1 
)
@type arm: str name of artm to be controlled, this must be initialized
   using setSelfGroups()
@param ref_{force, moment}: Target values at the target position.
                    Units: N, Nm, respectively.
@param {force, moment}_gain: multipliers to the eef offset position
                     vel_p and orientation vel_r. 3-dimensional
                     vector (then converted internally into a
                     diagonal matrix).

Definition at line 890 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.startImpedance_315_2 (   self,
  arm,
  M_p = 100.0,
  D_p = 100.0,
  K_p = 100.0,
  M_r = 100.0,
  D_r = 2000.0,
  K_r = 2000.0,
  force_gain = [1,
  moment_gain = [0,
  sr_gain = 1.0,
  avoid_gain = 0.0,
  reference_gain = 0.0,
  manipulability_limit = 0.1 
)
@type arm: str name of artm to be controlled, this must be initialized
   using setSelfGroups()
@param {force, moment}_gain: multipliers to the eef offset position
                     vel_p and orientation vel_r. 3-dimensional
                     vector (then converted internally into a
                     diagonal matrix).

Definition at line 958 of file hironx_client.py.

def hironx_ros_bridge.hironx_client.HIRONX.startImpedance_315_3 (   self,
  arm,
  M_p = 100.0,
  D_p = 100.0,
  K_p = 100.0,
  M_r = 100.0,
  D_r = 2000.0,
  K_r = 2000.0,
  force_gain = [1,
  moment_gain = [0,
  sr_gain = 1.0,
  avoid_gain = 0.0,
  reference_gain = 0.0,
  manipulability_limit = 0.1 
)
@type arm: str name of artm to be controlled, this must be initialized
   using setSelfGroups()
@param {force, moment}_gain: multipliers to the eef offset position
                     vel_p and orientation vel_r. 3-dimensional
                     vector (then converted internally into a
                     diagonal matrix).

Definition at line 996 of file hironx_client.py.

Definition at line 1085 of file hironx_client.py.

Definition at line 947 of file hironx_client.py.

Definition at line 1036 of file hironx_client.py.

Definition at line 1039 of file hironx_client.py.


Member Data Documentation

Initial value:
[[0], [0, 0],
                    [-0.6, 0, -100, 15.2, 9.4, 3.2],
                    [0.6, 0, -100, -15.2, 9.4, -3.2],
                    [0, 0, 0, 0],
                    [0, 0, 0, 0]]

Definition at line 292 of file hironx_client.py.

Initial value:
[[0], [0, 0],
                            [-0, 0, -130, 0, 0, 0],
                            [0, 0, -130, 0, 0, 0],
                            [0, 0, 0, 0],
                            [0, 0, 0, 0]]

Definition at line 300 of file hironx_client.py.

Initial value:
(" call is done. This does't necessarily mean " +
                               "the function call was successful, since not " +
                               "all methods internally called return status")

Definition at line 318 of file hironx_client.py.

Initial value:
[['torso', ['CHEST_JOINT0']],
              ['head', ['HEAD_JOINT0', 'HEAD_JOINT1']],
              ['rarm', ['RARM_JOINT0', 'RARM_JOINT1', 'RARM_JOINT2',
                        'RARM_JOINT3', 'RARM_JOINT4', 'RARM_JOINT5']],
              ['larm', ['LARM_JOINT0', 'LARM_JOINT1', 'LARM_JOINT2',
                        'LARM_JOINT3', 'LARM_JOINT4', 'LARM_JOINT5']]]

Definition at line 275 of file hironx_client.py.

dictionary hironx_ros_bridge::hironx_client.HIRONX::HandGroups = {'rhand': [2, 3, 4, 5], 'lhand': [6, 7, 8, 9]} [static]

Definition at line 308 of file hironx_client.py.

Definition at line 316 of file hironx_client.py.

Definition at line 330 of file hironx_client.py.

Definition at line 305 of file hironx_client.py.

Definition at line 306 of file hironx_client.py.

Initial value:
[[0],
               [0, 0],
               [25, -139, -157, 45, 0, 0],
               [-25, -139, -157, -45, 0, 0],
               [0, 0, 0, 0],
               [0, 0, 0, 0]]

Definition at line 285 of file hironx_client.py.

Definition at line 310 of file hironx_client.py.

Definition at line 313 of file hironx_client.py.

Definition at line 314 of file hironx_client.py.

Definition at line 330 of file hironx_client.py.


The documentation for this class was generated from the following file:


hironx_ros_bridge
Author(s): Kei Okada , Isaac I.Y. Saito
autogenerated on Thu Feb 21 2019 03:42:37