Indy APIs
회전행렬, 동차변환행렬, 순기구학, 역기구학 등 로봇의 기구학에 관한 인터페이스에서 부터 및 순동역학, 역동역학, 기본 제어기 등 로봇의 동역학에 관한 인터페이스까지 로봇 제어에 활용할 수 있는 다양한 기능들을 포함하고 있으며 "../NRMKFramework/Components/AbstractRobot6D.h" (IndyRP2의 경우 "AbstractRobot7D")에서 자세한 항목들을 찾아 볼 수 있다.
[순기구학: computeFK]
- AbstractRobot6D::computeFK
- Compute the task position and task velocity (optionally) from robot pose.
1 2 |
|
Parameters:
- TaskPosition: Construct a task position from homogeneous transformation (LieGroup::HTransform)
- TaskVelocity: Construct a task velocity from twist (LieGroup::Twist)
[자코비안: computeJacobian]
- AbstractRobot6D::computeJacobian
- Compute the task position, task velocity, task Jacobian, and task Jacobian derivative.
1 2 |
|
Parameters:
- J, Jdot: "Task Jacobian" and its time derivative, respectively
- TaskPosition: Construct a task position from homogeneous transformation (LieGroup::HTransform)
- TaskVelocity: Construct a task velocity from twist (LieGroup::Twist)
- TaskJacobian: 6 by 6 matrix (Eigen::Matrix
)
[역동역학: idyn]
- AbstractRobot6D::idyn
- Implement the recursive Newton-Euler method without gravity (optionally with gravity) for a given joint velocity and acceleration vector
1 2 |
|
Parameters
- qdot: Array of the joint velocity values
- qddot: Array of the joint acceleration values
- gacc: Gravitation acceleration vector
[수동적 역동역학: idyn_passive]
- AbstractRobot6D::idyn_passive
- Implement the recursive passivity-based Newton-Euler method without gravity (optionally with gravity) for a given joint velocity and acceleration vector
1 2 |
|
Parameters
- qdot: Array of the joint reference velocity values
- qddot: Array of the joint acceleration values
- gacc: Gravitation acceleration vector
[중력: idyn_gravity]
- AbstractRobot6D::idyn_gravity
- Implement the recursive Newton-Euler method for gravitation for a given joint position
1 |
|
Parameters
- gacc: Gravitation acceleration vector
[운동량: idyn_momentum]
- AbstractRobot6D::idyn_momentum
- Implement the recursive Newton-Euler method for momentum computation for a given joint acceleration vector.
1 |
|
Parameters:
- qddot: Array of the joint acceleration values
[동역학 파라미터:computeDynamicsParams]
- AbstractRobot6D::computeDynamicsParams
- Compute the task position, task velocity, task Jacobian, and task Jacobian derivative.
1 2 |
|
Parameters:
- M: Inertia matrix
- C: Coriolis and centrifugal matrix
- G: Gravity force vector
- gravDir: Direction of gravity force
[어드미턴스 궤적 생성: updateAdmitancTraj]
- Calculate the desired trajectory based on a virtual physical proxy with the inertia, floating on 3D space
- Use F/T sensor values to apply the external forces to a virtual proxy
Reset admittance trajectory:
1 |
|
Parameters:
- delT: Sampling time
Update admittance trajectory:
1 2 3 4 |
|
Parameters:
- TaskPosition: Construct a task position from homogeneous transformation (LieGroup::HTransform)
- TaskVelocity: Construct a task velocity from twist (LieGroup::Twist)
- TaskAcceleration: Construct a task acceleration from twist (LieGroup::Twist)
- posDes: Desired position trajectory calculated from interpolator
- velDes: Desired velocity trajectory calculated from interpolator
- accDes: Desired acceleration trajectory calculated from interpolator
- tposProxy: Proxy's desired position trajectory
- tvelProxy: Proxy's desired velocity trajectory
- taccproxy: Proxy's desired acceleration trajectory
- mode: 0 - not applied; 1 - applied for displacement; 2 - applied for rotation
[순동역학 위치제어: FowardDynController]
- AbstractRobot6D::ForwardDynController
- Provide "Forward Dynamic Controller" which uses "Jacobian Transpose" method in the task-space position control. It guarantees singularity-free task-space control.
Initialization and reset of Forward Dynamic Controller:
1 2 |
|
Parameters:
- delT: Sampling time
Control gain settings of Forward Dynamic Controller:
1 2 |
|
Parameters:
- kp, kv, ki: Position, velocity, and integral control gain, respectively
Forwad Dynamic Controller:
1 2 3 4 |
|
Parameters:
- AbstractRobot6D: 6 degree-of-freedom (DOF) robot class which includes its states and API functions as members
- TaskPosition: Construct a task position from homogeneous transformation (LieGroup::HTransform)
- TaskVelocity: Construct a task velocity from twist (LieGroup::Twist)
- TaskAcceleration: Construct a task acceleration from twist (LieGroup::Twist)
- JointMat: 6 by 6 matrix (Eigen::Matrix)
- robotNom: Nominal (or Simulated) robot
- Mn: Inertia matrix of nominal robot
- Cn: Coriolis and centrifugal matrix of nominal robot
- Gn: Gravity force vector of nominal robot
- PosDes, velDes: Desired position and velocity, respectively
[위치제어기: HinfController]
- AbstractRobot6D::HinfController
- Provide H-infinity position controller which is the fundamental position controller of Neuromeka's Indy7
Initialization and reset of H-infinity controller:
1 2 |
|
Parameters:
- delT: Sampling time
Control gain settings of H-infinity controller:
1 |
|
Parameters:
- kp, kv, ki: Position, velocity, integral control gains, respectively
Joint-space H-infinity controller and task-space H-infinity controller:
1 2 3 4 |
|
Parameters:
- qd, qdotd, qddotd: Desired joint position, joint velocity, and joint acceleration, respectively
- pd, pdotd, pddotd: Desired task position, task velocity, and task acceleration, respectively
- gravDir: Direction of gravity force
[타겟 좌표 설정: setTtarget]
- AbstractRobot6D::setTtarget
- Setting the HTransform matrix from last joint to TCP
1 |
|
Parameters:
- R: Rotation matrix from last joint to TCP
- r: Displacement vector from last joint to TCP
[참조 좌표계 설정: setTReference]
- AbstractRobot6D::setTReference
- Setting the HTransform matrix from global origin to Robot origin
1 |
|
Parameters:
- R: Rotation matrix from global origin to Robot origin
- r: Displacement vector from global origin to Robot origin
[6축 힘센서 좌표계 설정: setTFTSensor]
- AbstractRobot6D::setTFTSensor
- Setting the HTransform matrix from TCP to F/T sensor frame
1 |
|
Parameters:
- R: Rotation matrix from global origin to Robot origin
- r: Displacement vector from global origin to Robot origin
[툴 속성 설정]
- AbstractRobot6D::toolWeight, toolXcom, toolYcom, toolZcom
- Return the tool information such as tool weight and tool position.
1 2 |
|
1 2 |
|
1 2 |
|
1 2 |
|
[홈 위치 출력: qhome]
- AbstractRobot6D::qhome
- Return the current home position.
1 2 |
|