Skip to content

IndySDK API Documentation

IndySDK는 로봇 제어에 필수적인 운동학 및 동역학 계산을 위한 다양한 함수를 제공합니다. 자세한 정보는 "../NRMKFramework/Indy/Model" 디렉토리 내에 위치한 "AbstractRobotXD"를 참조하십시오.

이 문서는 다양한 카테고리로 구성된 API의 간략한 개요를 제공합니다.

General Conventions

Vector Representation

  • [\omega^T, v^T]^T

Units

  • 위치: 미터 (m)
  • 방향: 라디안 (rad)
  • 힘: 뉴턴 (N)
  • 토크: 뉴턴-미터 (Nm)

Frame References

  • 참조 프레임: 기본값은 로봇 베이스로 설정됩니다.
  • 목표 프레임: 기본값은 엔드 이펙터 / 마지막 바디 프레임으로 설정됩니다.

1. Kinematics APIs

IndySDK에는 로봇의 운동 및 구성을 계산하고 관리하기 위해 제공되는 다음과 같은 운동학 관련 함수들이 있습니다. 이러한 함수들은 정밀한 제어 및 운동 분석을 용이하게 하도록 설계되었습니다.

1.1. Forward Kinematics

AbstractRobotXD::computeFK

이 메서드는 로봇의 현재 포즈를 기반으로 작업 위치를 계산하고, 선택적으로 작업 속도를 계산합니다.

void computeFK(TaskPosition &pos)
void computeFK(TaskPosition &pos, TaskVelocity &vel)
  • Parameters
    • TaskPosition &pos: Represents the task position, which is derived from a homogeneous transformation (LieGroup::HTransform).
    • TaskVelocity &vel (Optional): Represents the task velocity, derived from a twist (LieGroup::Twist).

1.2. Jacobian

AbstractRobotXD::computeJacobian

이 함수는 작업 위치, 작업 속도, 작업 야코비안, 작업 야코비안의 도함수를 계산하여 동적 및 제어 계산에 필수적인 정보를 제공합니다.

void computeJacobian(TaskPosition &pos, TaskVelocity &vel, TaskJacobian &J, TaskJacobian &Jdot)
  • Parameters
    • TaskPosition &pos: Constructs a task position from a homogeneous transformation (LieGroup::HTransform).
    • TaskVelocity &vel: Constructs a task velocity from a twist (LieGroup::Twist).
    • TaskJacobian &J: The task Jacobian, represented as a 6x6 matrix (Eigen::Matrix).
    • TaskJacobian &Jdot: The time derivative of the Task Jacobian.

2. Robot Dynamics APIs

IndySDK는 특화된 수동성 기반의 재귀적 뉴턴-오일러 방법을 포함하여 역동학 계산을 위한 다양한 함수를 제공합니다. IndySDK는 또한 관성 행렬, 코리올리스 및 원심력 행렬, 그리고 중력 벡터와 같은 로봇 동역학을 계산하기 위한 함수도 포함합니다. 이 섹션에서는 관련 API의 개요를 제공합니다.

2.1. Inverse Dynamics

AbstractRobotXD::idyn

이 함수는 주어진 조인트 속도 및 가속도 벡터에 대해 지상 시스템을 위한 재귀적 뉴턴-오일러 방법(중력은 선택 사항)을 구현합니다.

void idyn(JointVec const & qdot, JointVec const & qddot)
void idyn(JointVec const & qdot, JointVec const & qddot, LieGroup::Vector3D const & gacc)
  • Parameters
    • JointVec const &qdot: Joint velocity vector.
    • JointVec const &qddot: Joint acceleration vector.
    • LieGroup::Vector3D const &gacc (Optional): Gravity acceleration vector.

2.2. Passive Inverse Dynamics

AbstractRobotXD::idyn_passive

이 함수는 주어진 조인트 속도 및 가속도 벡터에 대해 지상 시스템에 대한 재귀적인 수동성 기반 뉴턴-오일러 방법(중력은 선택적)을 구현합니다.

void idyn_passive(JointVec const &qdot, JointVec const &qddot)
void idyn_passive(JointVec const &qdot, JointVec const &qddot, LieGroup::Vector3D const &gacc)
  • Parameters
    • JointVec const &qdot: Joint reference velocity vector.
    • JointVec const &qddot: Joint acceleration vector.
    • LieGroup::Vector3D const &gacc (Optional): Gravity acceleration vector.

2.3. Gravity

AbstractRobotXD::idyn_gravity

이 함수는 주어진 조인트 위치에서 지상 및 부유 시스템을 위해 중력만을 대상으로 하는 재귀적 뉴턴-오일러 방법을 구현합니다.

void idyn_gravity(LieGroup::Vector3D const &gacc)
  • Parameters
    • LieGroup::Vector3D const &gacc: Gravity acceleration vector.

2.4. Momentum

AbstractRobotXD::idyn_momentum

이 함수는 지정된 조인트 가속도 벡터를 사용하여 지상 시스템의 운동량을 재귀적 뉴턴-오일러 방법을 사용하여 계산합니다.

void idyn_momentum(JointVec const &qddot)
  • Parameters
    • JointVec const &qddot: Joint acceleration vector.

2.4. Dynamics Parameters

AbstractRobotXD::computeDynamicsParams

이 함수는 주어진 중력 방향에 대해 관성 행렬, 코리올리스 및 원심력 행렬, 그리고 중력력 벡터를 포함한 동적 매개변수를 계산합니다.

void computeDynamicsParams(LieGroup::Vector3D const &gravDir, JointMat &M, JointMat &C, JointVec &G)
  • Parameters
    • LieGroup::Vector3D const &gravDir: Direction of gravity force.
    • JointMat &M: Inertia matrix.
    • JointMat &C: Coriolis and centrifugal matrix.
    • JointVec &G: Gravity force vector.

3. H-infinity Controller APIs

뉴로메카는 IndySDK 사용자를 위한 내장 위치 제어기를 제공합니다. 이 섹션에서는 관절 공간 및 작업 공간 제어를 위한 특별한 유형의 위치 제어기, \mathcal{H}_\infty 최적 제어기를 사용하기 위한 사용 가능한 API를 강조합니다. \mathcal{H}_\infty 최적 제어기에서는 주로 두 가지 용어, 피드포워드와 피드백 용어가 있습니다. 피드포워드 용어는 참조 속도(\dot{q}_{ref})와 로봇 모델로부터 계산됩니다. 피드백 용어는 \mathcal{H}_\infty 최적성의 의미에서 방해와 모델 불확실성을 감쇠시키기 위해 추가됩니다.

\tau = \widehat{M}(q)\ddot{q}_{\text{ref}} + \widehat{C}(q,\dot{q})\dot{q}_{\text{ref}} + \widehat{g}(q) + K\dot{e}_{\text{ref}},

여기서 \widehat{M}, \widehat{C}, \widehat{g}는 각각 관성 행렬, 코리올리스 행렬, 그리고 중력 벡터를 나타냅니다. 참조 속도 오류는 다음과 같이 계산할 수 있습니다, \dot{e}_{\text{ref}} = \dot{q}_{\text{ref}} - \dot{q}. 참조 가속도(\ddot{q}_{\text{ref}})는 다음과 같이 정의됩니다.

\ddot{q}_{\text{ref}} = \ddot{q}_{\text{des}} + K_{v}\dot{e} + K_{p}e,\quad \dot{q}_{\text{ref}} = \dot{q}_{\text{des}} + K_{v}e + K_{p}\int{e},

여기서 e = q_{\text{des}} - q,는 관절 위치 오류이고 q_{\text{des}}는 원하는 위치 궤적입니다. K, K_{v}, K_{p}는 제어 이득입니다.

더 자세한 내용은 아래 논문에서 제시된 포괄적인 분석을 참조하시기 바랍니다.

3.1. Initialize H-Infinity Controller

AbstractRobotXD::initHinfController

이 함수는 적분 오류 계산 목적을 위해 지정된 제어 주기로 H-무한대 컨트롤러를 초기화하고, 수동성 기반 역동학을 설정합니다.

void initHinfController(double delt)
  • Parameters
    • double delt: Control period.

3.2. Reset H-Infinity Controller

AbstractRobotXD::resetHinfController

이 함수는 H-무한대 컨트롤러 내의 적분 오류를 재설정합니다.

void resetHinfController()
  • Parameters
    • None

3.3. Set H-Infinity Control Gains

AbstractRobotXD::setHinfControlGain

이 함수는 지정된 컨트롤러를 위한 H-무한대 컨트롤러의 이득 매개변수를 구성합니다.

void setHinfControlGain(const JointVec &kp, const JointVec &kv, const JointVec &ki, const int &mode)
  • Parameters
    • const JointVec &kp: Position gain vector.
    • const JointVec &kv: Damping gain vector.
    • const JointVec &ki: Integral gain vector.
    • const int &mode: Control mode (0 for joint control, 1 for task control).

3.4. H-Infinity Controller for Joint Space Control

AbstractRobotXD::HinfController

이 함수는 로봇의 현재 상태를 고려하여 원하는 조인트 위치, 속도 및 가속도를 기반으로 조인트 공간 제어를 위한 원하는 토크를 계산합니다.

void HinfController(LieGroup::Vector3D const &grav, JointVec const &qd, JointVec const &qdotd, JointVec const &qddotd)
  • Parameters
    • LieGroup::Vector3D const &grav: Gravity force direction.
    • JointVec const &qd: Desired joint position vector.
    • JointVec const &qdotd: Desired joint velocity vector.
    • JointVec const &qddotd: Desired joint acceleration vector.

3.5. H-Infinity Controller for Task Space Control

AbstractRobotXD::HinfController

이 함수는 로봇의 현재 상태를 고려하여 원하는 작업 위치, 속도 및 가속도를 기반으로 작업 공간 제어를 위한 원하는 토크를 계산합니다.

int HinfController(LieGroup::Vector3D const &grav, ExtendedPosition const &pd, ExtendedVelocity const &pdotd, ExtendedAcceleration const &pddotd)
  • Parameters
    • LieGroup::Vector3D const &grav: Gravity force direction.
    • ExtendedPosition const &pd: Desired task position vector.
    • ExtendedVelocity const &pdotd: Desired task velocity vector.
    • ExtendedAcceleration const &pddotd: Desired task acceleration vector.

4. Task Space Control APIs using a Forward Dynamics Approach

뉴로메카는 IndySDK 사용자를 위해 전방 동역학 기반 제어(FDC) 프레임워크를 기반으로 한, 운동학적 특이점이 없는 특별한 작업 공간 제어를 내장 제공합니다. 전방 동역학 로봇 시뮬레이션과 임피던스 컨트롤러 개념을 결합함으로써, FDC 프레임워크는 고이득 PD 제어와 견고한 내부 루프 보상기 구조를 통합하여 특이점 근처에서의 자세 추적 정확도와 안정성을 향상시킵니다.

자세한 내용은 다음 연구 논문을 참조하십시오.

4.1. Forward Dynamics Controller

AbstractRobotXD::ForwardDynController

이 함수는 로봇의 동역학을 고려하여 원하는 작업 궤적을 따르기 위한 원하는 조인트 토크를 계산합니다. 원하는 조인트 토크를 계산하기 위해 로봇의 공칭 모델을 사용합니다.

void ForwardDynController(AbstractRobot &robotNom, JointMat &Mn, JointMat &Cn, JointVec &Gn, ExtendedPosition const &posDes, ExtendedVelocity const &velDes, LieGroup::Vector3D const &gravDir)
  • Parameters
    • AbstractRobot &robotNom: nominal robot model.
    • JointMat &Mn: Inertia matrix.
    • JointMat &Cn: Coriolis and centrifugal matrix.
    • JointVec &Gn: Gravity vector.
    • ExtendedPosition const &posDes: Desired task position vector.
    • ExtendedVelocity const &velDes: Desired task velocity vector.
    • LieGroup::Vector3D const &gravDir: Direction of gravity force.

4.2. Set Forward Dynamics Control Gains

AbstractRobotXD::setForwardDynControlGain

이 함수는 번역 및 회전에 대한 가상 질량 및 강성을 포함한 전진 동역학 제어를 위한 이득 매개변수를 정의합니다.

void setForwardDynControlGain(JointVec const &kp, JointVec const &kv, JointVec const &ki, double const massxyz, double const massuvw, double const stiffnessxyz, double const stiffnessuvw)
  • Parameters
    • JointVec const &kp: Proportional gain vector.
    • JointVec const &kv: Damping gain vector.
    • JointVec const &ki: Integral gain vector.
    • double const massxyz: Virtual mass for translational movements.
    • double const massuvw: Virtual mass for rotational movements.
    • double const stiffnessxyz: Virtual stiffness for translational movements.
    • double const stiffnessuvw: Virtual stiffness for rotational movements.

4.3. Initialize Forward Dynamics Controller

AbstractRobotXD::initForwardDynController

이 함수는 제어 주기를 설정하고 지정된 시간 단계에 기반한 동적 작동을 위해 시스템을 준비함으로써 전진 동역학 컨트롤러를 초기화합니다.

void initForwardDynController(double delt)
  • Parameters
    • double delt: Control period.

4.4. Reset Forward Dynamics Controller

AbstractRobotXD::resetForwardDynController

이 함수는 전진 동역학 컨트롤러의 상태를 재설정하고, 적분 오류를 리셋합니다.

void resetForwardDynController()
  • Parameters
  • None

4.5 robot.computeTaskErr() Function

robot.computeTaskErr() 함수는 로봇 시스템에서 작업 프레임 오류를 계산하는 데 사용됩니다. 이 함수는 로봇의 실제 상태와 원하는 상태 간의 회전 및 위치 오류를 계산합니다.

  • 회전 오류 (err_rot): 라디안 단위로 측정됩니다.
  • 위치 오류 (err_pos): 미터 단위로 측정됩니다.

Rotation Error Calculation

회전 오류는 다음과 같이 계산됩니다:

  • Rtilde = R.icascade(Rd); // 회전 행렬을 계산
  • err_rot = Rtilde.expCoord(); // 지수 좌표를 추출

Position Error Calculation

위치 오류는 다음과 같이 계산됩니다:

  • err_pos = desired_position – actual_position;
    • 여기서 desired_position과 actual_position은 각각 목표 위치와 현재 위치를 나타내는 벡터입니다.

5. Admittance Control APIs

뉴로메카는 외부 힘에 기반한 준수 제어 목적으로 원하는 작업 궤적을 업데이트하는 특별한 기능을 내장하고 있습니다. 이 컨트롤러는 로봇의 엔드 이펙터에 부착된 힘/토크 센서를 통해 외부 접촉에 대해 유연하게 반응합니다. 뉴로메카의 IndySDK는 외부 힘에 대응하여 원하는 작업 궤적을 조정하는 특화된 내장 기능을 포함하고 있으며, 준수 제어를 가능하게 하는 것을 목표로 합니다. 이 기능은 컨트롤러가 외부 접촉에 적응적으로 반응하도록 하여, 로봇의 엔드 이펙터에 부착된 힘/토크 센서를 이용한 유연한 행동을 가능하게 합니다.

5.1. Reset Admittance Trajectory

AbstractRobotXD::resetAdmittanceTraj

이 함수는 프록시 궤적을 재설정하고 프록시 위치 궤적을 로봇의 현재 TCP (Tool Center Point) 포즈로 설정합니다. 또한 공칭 로봇을 시뮬레이션하기 위한 시간 단계로 제어 주기를 설정합니다.

virtual void resetAdmittanceTraj(double delT)
  • Parameters
    • double delT: Control period.

5.2. Update Admittance Trajectory

AbstractRobotXD::updateAdmittanceTraj

이 함수는 적용된 외부 힘을 기반으로 원하는 TCP 궤적을 업데이트하고 이러한 궤적을 프록시 궤적으로 설정합니다. 지정된 모드에 따라 번역, 회전 또는 둘 모두에서 선택적인 유연성을 허용합니다.

virtual void updateAdmittanceTraj(const Vector &posDes, const Vector &velDes, const Vector &accDes, Vector &tposProxy, Vector &tvelProxy, Vector &taccProxy, const Vector &f_ext, const Vector &f_ext_filtered, int mode)
  • Parameters
    • const Vector &posDes: Desired task position vector.
    • const Vector &velDes: Desired task velocity vector.
    • const Vector &accDes: Desired task acceleration vector.
    • Vector &tposProxy: Proxy task position vector.
    • Vector &tvelProxy: Proxy task velocity vector.
    • Vector &taccProxy: Proxy task acceleration vector.
    • const Vector &f_ext: External force.
    • const Vector &f_ext_filtered: Filtered external force.
    • int mode: Mode to select compliance direction (translation/rotation).
      • mode = 0: No update to the TCP trajectories (pure position control).
      • mode = 1: Only the displacement component will be compliant. The rotation component is pure position control.
      • mode = 2: Only the rotation component will be compliant. The displacement component is pure position control.
      • mode = any other number: Both displacement and rotational components will be compliant.

6. Coordinate and Property Setting APIs

이 섹션은 로봇 구성 요소의 공간적 관계와 속성을 정확하게 정의하는 데 필수적인 좌표 및 속성을 설정하기 위한 API를 소개합니다. 대상 좌표, 기준 좌표, F/T 센서 좌표, 도구 속성 설정을 다룹니다.

6.1. Target Coordinate Setting

AbstractRobotXD::setTtarget

이 함수는 마지막 조인트에서 TCP (Tool Center Point)로의 변환을 정의하는 HTransform 행렬을 설정합니다.

void setTtarget(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from the last joint to TCP.
    • LieGroup::Displacement const &r: Displacement vector from the last joint to TCP.

6.2. Reference Coordinate Setting

AbstractRobotXD::setTReference

이 함수는 글로벌 원점에서 로봇의 베이스 원점으로의 HTransform 행렬을 설정합니다.

void setTReference(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from the global origin to the robot's origin.
    • LieGroup::Displacement const &r: Displacement vector from the global origin to the robot's origin.

6.3. F/T Sensor Coordinate Setting

AbstractRobotXD::setTFTSensor

이 함수는 TCP에서 F/T (Force/Torque) 센서의 프레임으로의 HTransform 행렬을 설정합니다.

void setTFTSensor(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from TCP to F/T sensor frame.
    • LieGroup::Displacement const &r: Displacement vector from TCP to F/T sensor frame.

6.4. Tool Property Setting

AbstractRobotXD::toolWeight, toolXcom, toolYcom, toolZcom

이 함수는 도구의 속성(예: 무게 및 질량 중심 좌표)에 접근을 제공합니다.

double const &toolWeight()
double &toolWeight()
double const &toolXcom()
double &toolXcom()
double const &toolYcom()
double &toolYcom()
double const &toolZcom()
double &toolZcom()