Skip to content

How to Execute the IndySDK

IndySDK Components

By default, IndySDK users can build and execute components that replace the Joint Controller and the Task Controller.

Component Deploy Name in JSON Description
Joint Controller (MoveJ) CustomJointController Calculates command torque for each joint based on target joint angles.
Task Controller (MoveL) CustomTaskController Calculates command torque for each joint based on target task space position.

Note

The torque calculation function is called at every real-time cycle within the Indy Framework. It is crucial that the computation time of this function does not exceed the cycle time.

For more information, see the following file. src_cpp/NRMKFramework/AbstractComponent/ControlAlgorithm.h

template<typename RobotType>
class ControlAlgorithm : public AlgorithmHolder
{
protected:
    typedef NRMKConfig::ControlGains<RobotType::JOINT_DOF> ControlGains;
    typedef NRMKConfig::CustomControlGains<RobotType::JOINT_DOF> CustomControlGains;
    typedef NRMKMotion::MotionDataPack<RobotType::JOINT_DOF> MotionData;
    typedef NRMKControl::ControlDataPack<RobotType::JOINT_DOF> ControlData;

public:
    typedef RobotType ROBOT;
    typedef typename ROBOT::JointVec JointVec;
    typedef typename ROBOT::JointMat JointMat;

    virtual ~ControlAlgorithm() = default;
    virtual void initialize(ROBOT & robot, double delt) = 0;
    virtual void setGains(const ControlGains &gains) {} // non-pure virtual function
    virtual void reset() {}; // non-pure virtual function
    virtual void reset(ROBOT & robot) {}  // non-pure virtual function
    virtual void reset(int index) { reset(); }
    virtual void setMode(uint64_t& mode) { _controlMode = mode;}
    virtual uint64_t& getMode() { return _controlMode;}  /**< integer control modes for custom controller variations | 0: default controller, 1~: reserved for custom controller */

    virtual void compute(ROBOT &robot, const LieGroup::Vector3D &gravDir, const MotionData &motionData,
                         ControlData &controlData) = 0;

    virtual void setCustomGains(const CustomControlGains & gains) {
        for (int i = 0; i < RobotType::JOINT_DOF; ++i) {
            gain0[i] = gains.customGains.gain0[i];
            gain1[i] = gains.customGains.gain1[i];
            gain2[i] = gains.customGains.gain2[i];
            gain3[i] = gains.customGains.gain3[i];
            gain4[i] = gains.customGains.gain4[i];
            gain5[i] = gains.customGains.gain5[i];
            gain6[i] = gains.customGains.gain6[i];
            gain7[i] = gains.customGains.gain7[i];
            gain8[i] = gains.customGains.gain8[i];
            gain9[i] = gains.customGains.gain9[i];
        }
    }

protected:
    JointVec gain0, gain1, gain2, gain3, gain4, gain5, gain6, gain7, gain8, gain9;
private:
    uint64_t _controlMode = 0U;
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW

};

Abstract Component: Control Algorithm

Joint Control

The Joint Control component allows applying torque to each joint based on the target position, speed, acceleration, and kinematic/dynamic information within the joint space. The calculated joint torque is transmitted directly to the motor drive of each joint.

The target position, speed, and acceleration for each joint can be checked through the following structure:

const JointVec &qDes = motionData.motionPoint.qd;
const JointVec &qdotDes = motionData.motionPoint.qdotd;
const JointVec &qddotDes = motionData.motionPoint.qddotd;

Task Control

The Task Control component enables the calculation and application of target joint torque based on the target position and actual robot position information in 6D space. The calculated joint torque is transmitted directly to the motor drive of each joint.

The target position, speed, and acceleration in the task space can be checked through the following structure:

const JointVec &pDes = motionData.motionPoint.pd;
const JointVec &pdotDes = motionData.motionPoint.pdotd;
const JointVec &pddotDes = motionData.motionPoint.pddotd;

Apply the Plugin Components

This section guides you on how to apply pre-installed plugin components.

Plugin Components Path

To verify if the component files are installed, connect to the control box via SSH and check the following path:

- home/user/release/IndyDeployment
   └─ PluginComponents
        ├─ CustomJointControllerCreator.comp
        └─ CustomTaskControlCreator.comp

Ensure the Components.json file in the following path lists the names of the components:

- home/user/release/IndyConfigurations
   └─ Cobot
        ├─ ...
        ├─ Plugins
        │    └─ Components.json
        └─ ...    

Components.json

{
    "JointController": "CustomJointControlCreator",
    "TaskController": "CustomTaskControlCreator"
}

Here, the component assigned to JointController replaces the joint controller (MoveJ), and the component assigned to TaskController replaces the task controller (MoveL).

Users can replace the control components in Components.json with their own built components by copying them to the /home/user/release/IndyDeployment/PluginComponents directory.

**Robot Software Restart **

After changing the custom controller, restart the robot software. There are two main ways to do this:

Method 1:

  1. Turn off the robot software using the following command:

    sudo killall –g UDEVMonitor
    

  2. Navigate to the deployment directory:

    cd /home/user/release/IndyDeployment/
    

  3. Start the robot software:

    sudo python3 indy_run.py
    
    Press CTRL+C to turn off the software that was started manually.

Method 2:

  1. Reboot the control box using the following command:
    sudo reboot
    

Activate Your Controller Using IndyDCP3

  • Activation can be done as follows using IndyDCP3:
  • This allows control of the actual robot or simulation robot through Conty or the Indy API.

Note

When the robot is in Idle mode, the default controller operates. During the execution of MoveJ and MoveL motions through Conty or the Indy API, the user's controller takes over. MoveJ and MoveL can also be executed from Conty's "Move" tab during jog motion and added through the "Program" tab. For detailed information about motion operation, please refer to the Conty manual and IndyAPI manual.