Basic RT components and utilities  315.12.1

Overview

This component is cartesian impedance control, in which it modifies end-effector's position or orientation based on force/torque.

Feature

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.

Mode

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

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_idImpedanceController
categoryexample

Data Ports

Input Ports

port namedata typeunitdescription
qCurrentRTC::TimedDoubleSeq[rad]Actual joint angles
qRefRTC::TimedDoubleSeq[rad]Reference joint angles
rpyRTC::TimedOrientation3D[rad]Actual attitude sensor's Roll-Pitch-Yaw angle
rpyRefRTC::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

Output Ports

port namedata typeunitdescription
qRTC::TimedDoubleSeq[rad]Output reference joint angles

Service Ports

Service Providers

port nameinterface nameservice typeIDLdescription
ImpedanceControllerServiceservice0ImpedanceControllerServiceOpenHRP::ImpedanceControllerServiceImpedanceControllerService

Service Consumers

N/A

Configuration Variables

nametypeunitdefault valuedescription
debugLevelint0debug level

Configuration File

N/A