Basic RT components and utilities
315.12.1
|
This component is cartesian impedance control, in which it modifies end-effector's position or orientation based on force/torque.
This component receives reference joint angles from "qRef" inport and actual force/torque values. Then it calculates reference end-effector position and orientation and modifies end-effector's position/orientation based on force/torque. It solves Inverse Kinematics based on modified end-effector position/orientation, obtains jonint angles, and outputs the joint angles as "q" outport.
This component has modes by JointGroup such as ``rarm`` and ``rleg``. By default, this component is idle mode for all JointGroup, in which it do not modify input joint angles. When OpenHRP::ImpedanceControllerService::setImpedanceControllerParam() are called in idle mode, it switches to controlling mode, in which it modifies input joint angles. When OpenHRP::ImpedanceControllerService::deleteImpedanceController() are called in controlling mode, it switches to idle mode.
ImpedanceOutputGenerator example to learn ImpedanceController response.
Users can change test type (step responce for reference force, ramp response for reference position, ... etc).
testImpedanceOutputGenerator [test-type-option] # Non ROS environment rosrun hrpsys testImpedanceOutputGenerator [test-type-option] # ROS environment
[test-type-option] is test type.
To learn test type, please execute testImpedanceOutputGenerator without arguments.
implementation_id | ImpedanceController |
---|---|
category | example |
port name | data type | unit | description |
---|---|---|---|
qCurrent | RTC::TimedDoubleSeq | [rad] | Actual joint angles |
qRef | RTC::TimedDoubleSeq | [rad] | Reference joint angles |
rpy | RTC::TimedOrientation3D | [rad] | Actual attitude sensor's Roll-Pitch-Yaw angle |
rpyRef | RTC::TimedOrientation3D | [rad] | Reference attitude sensor's Roll-Pitch-Yaw angle |
name of force/torque sensor defined in a VRML model, such as "rhsensor" | RTC::TimedDoubleSeq | [N],[Nm] | Actual force/torque in the sensor frame |
port name | data type | unit | description |
---|---|---|---|
q | RTC::TimedDoubleSeq | [rad] | Output reference joint angles |
port name | interface name | service type | IDL | description |
---|---|---|---|---|
ImpedanceControllerService | service0 | ImpedanceControllerService | OpenHRP::ImpedanceControllerService | ImpedanceControllerService |
N/A
name | type | unit | default value | description |
---|---|---|---|---|
debugLevel | int | 0 | debug level |
N/A