PID Dynamixel XL-320

Hello everyone! I’m new to control system and Robotis product. So, I have a problem related to changing the PID value of the XL-320. So, I use system identification in Matlab to obtain the transfer function (using the goal and present position detected by the XL-320), then tune the Kp, Ki and Kd value to get the desired response of the system. Then, I try to put those (Kp, Ki, Kd) values to the Dynamixel XL-320 via Dynamixel Wizard 2 + OpenRB-150 and also try it in the Dynamixel+Arduino Uno, but both of the final response doesn’t change at all . Here attach the code that I used in the Arduino. Does anyone know what my problem is and how to solve this problem? Thank you in advance!

Regards,
Eka

/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*     http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/

/** Please refer to each DYNAMIXEL eManual(http://emanual.robotis.com) for supported Operating Mode
 * Operating Mode
 *  1. OP_POSITION                (Position Control Mode in protocol2.0, Joint Mode in protocol1.0)
 *  2. OP_VELOCITY                (Velocity Control Mode in protocol2.0, Speed Mode in protocol1.0)
 *  3. OP_PWM                     (PWM Control Mode in protocol2.0)
 *  4. OP_EXTENDED_POSITION       (Extended Position Control Mode in protocol2.0, Multi-turn Mode(only MX series) in protocol1.0)
 *  5. OP_CURRENT                 (Current Control Mode in protocol2.0, Torque Mode(only MX64,MX106) in protocol1.0)
 *  6. OP_CURRENT_BASED_POSITION  (Current Based Postion Control Mode in protocol2.0 (except MX28, XL430))
 */

#include <DynamixelShield.h>


#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
  #include <SoftwareSerial.h>
  SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
  #define DEBUG_SERIAL soft_serial
#elif defined(ARDUINO_SAM_DUE) || defined(ARDUINO_SAM_ZERO)
  #define DEBUG_SERIAL SerialUSB    
#else
  #define DEBUG_SERIAL Serial
#endif

const uint8_t DXL_ID = 3;
const float DXL_PROTOCOL_VERSION = 2.0;
int32_t goal_position[2] = {900, 1000};
int8_t direction = 0;
unsigned long timer = 0;

// Position PID Gains
// Adjust these gains to tune the behavior of DYNAMIXEL
uint16_t position_p_gain = 1;
uint16_t position_i_gain = 20;
uint16_t position_d_gain = 0;

DynamixelShield dxl;

//This namespace is required to use Control table item names
using namespace ControlTableItem;

void setup() {
  // put your setup code here, to run once:
  
  // For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
  DEBUG_SERIAL.begin(115200);

  
  // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
  dxl.begin(1000000);
  // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
  dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
  // Get DYNAMIXEL information
  dxl.ping(DXL_ID);

  // put your main code here, to run repeatedly:
  
  // Position Control Mode in protocol2.0, Joint Mode in protocol1.0
  // Turn off torque when configuring items in EEPROM area
  dxl.torqueOff(DXL_ID);
  dxl.setOperatingMode(DXL_ID, OP_POSITION);
  dxl.torqueOn(DXL_ID);

  // Set Position PID Gains
  dxl.writeControlTableItem(POSITION_P_GAIN, DXL_ID, position_p_gain);
  dxl.writeControlTableItem(POSITION_I_GAIN, DXL_ID, position_i_gain);
  dxl.writeControlTableItem(POSITION_D_GAIN, DXL_ID, position_d_gain);
}

void loop(){

  while(true) {
    DEBUG_SERIAL.print("Goal_Position:");
    DEBUG_SERIAL.print(dxl.readControlTableItem(GOAL_POSITION, DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.print("Present_Position:");
    DEBUG_SERIAL.print(dxl.getPresentPosition(DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.println();
    delay(10);

    if (millis() - timer >= 2000) {
      dxl.setGoalPosition(DXL_ID, goal_position[direction]);
      timer = millis();
      break;
    }
  }

  if(direction >= 1) {
    direction = 0;
  } else {
    direction = 1;
  }

  

  
}

Please first check the actual control table for the XL-320:

There you will see that the Goal Position needs only 16 bit and the PID gains are only 8 bits. Most likely this is the problem. The XL-320 is the oldest actuator of the XL series so its settings are very different from the newer XL actuators.

Also these parameters are in the RAM area so they will be reset to default values after you power them down.

Hello, thanks for your answer. I try your suggestion, but it seems like there is no different. Here attached the response figure and the new code. Do I make any mistake? Thank you!

Regards,
Eka

/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*     http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/

/** Please refer to each DYNAMIXEL eManual(http://emanual.robotis.com) for supported Operating Mode
 * Operating Mode
 *  1. OP_POSITION                (Position Control Mode in protocol2.0, Joint Mode in protocol1.0)
 *  2. OP_VELOCITY                (Velocity Control Mode in protocol2.0, Speed Mode in protocol1.0)
 *  3. OP_PWM                     (PWM Control Mode in protocol2.0)
 *  4. OP_EXTENDED_POSITION       (Extended Position Control Mode in protocol2.0, Multi-turn Mode(only MX series) in protocol1.0)
 *  5. OP_CURRENT                 (Current Control Mode in protocol2.0, Torque Mode(only MX64,MX106) in protocol1.0)
 *  6. OP_CURRENT_BASED_POSITION  (Current Based Postion Control Mode in protocol2.0 (except MX28, XL430))
 */

#include <DynamixelShield.h>


#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
  #include <SoftwareSerial.h>
  SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
  #define DEBUG_SERIAL soft_serial
#elif defined(ARDUINO_SAM_DUE) || defined(ARDUINO_SAM_ZERO)
  #define DEBUG_SERIAL SerialUSB    
#else
  #define DEBUG_SERIAL Serial
#endif

const uint8_t DXL_ID = 3;
const float DXL_PROTOCOL_VERSION = 2.0;

int16_t goal_position[2] = {900, 1000};
int8_t direction = 0;
unsigned long timer = 0;

// Position PID Gains
// Adjust these gains to tune the behavior of DYNAMIXEL
uint8_t position_p_gain = 200;
uint8_t position_i_gain = 100;
uint8_t position_d_gain = 100;

DynamixelShield dxl;

//This namespace is required to use Control table item names
using namespace ControlTableItem;

void setup() {
  // put your setup code here, to run once:
  
  // For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
  DEBUG_SERIAL.begin(115200);

  
  // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
  dxl.begin(1000000);
  // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
  dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
  // Get DYNAMIXEL information
  dxl.ping(DXL_ID);

  // put your main code here, to run repeatedly:
  
  // Position Control Mode in protocol2.0, Joint Mode in protocol1.0
  // Turn off torque when configuring items in EEPROM area
  dxl.torqueOff(DXL_ID);
  dxl.setOperatingMode(DXL_ID, OP_POSITION);
  dxl.torqueOn(DXL_ID);

  // Set Position PID Gains
  dxl.writeControlTableItem(P_GAIN, DXL_ID, position_p_gain);
  dxl.writeControlTableItem(I_GAIN, DXL_ID, position_i_gain);
  dxl.writeControlTableItem(D_GAIN, DXL_ID, position_d_gain);
  
}

void loop(){

  while(true) {
    DEBUG_SERIAL.print("");
    DEBUG_SERIAL.print(dxl.readControlTableItem(GOAL_POSITION, DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.print("");
    DEBUG_SERIAL.print(dxl.getPresentPosition(DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.println();
    delay(10);

    if (millis() - timer >= 2000) {
      dxl.setGoalPosition(DXL_ID, goal_position[direction]);
      timer = millis();
      break;
      
    }
  }

  if(direction >= 1) {
    direction = 0;
  } else {
    direction = 1;
  }

  

  
}

Response with Kp, Ki, Kd = 0;
image

Response with Kp = 200, Ki = 100, Kd = 100;
image

Can you implement in the loop some ReadControlTableItem() for the PID gains to see if the numbers you’ve set are really there?

Also I am assuming that you have read this post?

Hello there! Thanks for the suggestion about checking the control table and the size of the PID Gains. After trial and error, I found out that the the Goal Position is int32_t and the PID Gain also int32_t. I try those number based on the description of the dxl class in the DynamixelShield library. I try to change the value of the gains, and it does make differences, although I have not find my “desired” response. I also try to print the PID gain via ReadControlTableItem(), it shown the correct values as per my code. Here attached the new code and the new response. Thanks!
image

/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*     http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/

/** Please refer to each DYNAMIXEL eManual(http://emanual.robotis.com) for supported Operating Mode
 * Operating Mode
 *  1. OP_POSITION                (Position Control Mode in protocol2.0, Joint Mode in protocol1.0)
 *  2. OP_VELOCITY                (Velocity Control Mode in protocol2.0, Speed Mode in protocol1.0)
 *  3. OP_PWM                     (PWM Control Mode in protocol2.0)
 *  4. OP_EXTENDED_POSITION       (Extended Position Control Mode in protocol2.0, Multi-turn Mode(only MX series) in protocol1.0)
 *  5. OP_CURRENT                 (Current Control Mode in protocol2.0, Torque Mode(only MX64,MX106) in protocol1.0)
 *  6. OP_CURRENT_BASED_POSITION  (Current Based Postion Control Mode in protocol2.0 (except MX28, XL430))
 */

#include <DynamixelShield.h>


#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
  #include <SoftwareSerial.h>
  SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
  #define DEBUG_SERIAL soft_serial
#elif defined(ARDUINO_SAM_DUE) || defined(ARDUINO_SAM_ZERO)
  #define DEBUG_SERIAL SerialUSB    
#else
  #define DEBUG_SERIAL Serial
#endif

const uint8_t DXL_ID = 3;
const float DXL_PROTOCOL_VERSION = 2.0;
int32_t goal_position[2] = {900, 1000};
int8_t direction = 0;
unsigned long timer = 0;

// Position PID Gains
// Adjust these gains to tune the behavior of DYNAMIXEL
int32_t position_p_gain = 50;
int32_t position_i_gain = 0;
int32_t position_d_gain = 0;

DynamixelShield dxl;

//This namespace is required to use Control table item names
using namespace ControlTableItem;

void setup() {
  // put your setup code here, to run once:
  
  // For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
  DEBUG_SERIAL.begin(115200);

  
  // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
  dxl.begin(1000000);
  // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
  dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
  // Get DYNAMIXEL information
  dxl.ping(DXL_ID);

  // put your main code here, to run repeatedly:
  
  // Position Control Mode in protocol2.0, Joint Mode in protocol1.0
  // Turn off torque when configuring items in EEPROM area
  dxl.torqueOff(DXL_ID);
  dxl.setOperatingMode(DXL_ID, OP_POSITION);
  dxl.torqueOn(DXL_ID);

  // Set Position PID Gains
  dxl.writeControlTableItem(P_GAIN, DXL_ID, position_p_gain);
  dxl.writeControlTableItem(I_GAIN, DXL_ID, position_i_gain);
  dxl.writeControlTableItem(D_GAIN, DXL_ID, position_d_gain);
}

void loop(){

  while(true) {
    DEBUG_SERIAL.print("Goal_Position:");
    DEBUG_SERIAL.print(dxl.readControlTableItem(GOAL_POSITION, DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.print("Present_Position:");
    DEBUG_SERIAL.print(dxl.getPresentPosition(DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.println();
    DEBUG_SERIAL.print("P:");
    DEBUG_SERIAL.print(dxl.readControlTableItem(P_GAIN, DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.print("I:");
    DEBUG_SERIAL.print(dxl.readControlTableItem(I_GAIN, DXL_ID));
    DEBUG_SERIAL.print(",");
    DEBUG_SERIAL.print("D:");
    DEBUG_SERIAL.print(dxl.readControlTableItem(D_GAIN, DXL_ID));
    DEBUG_SERIAL.print(",");

    delay(100);

    if (millis() - timer >= 2000) {
      dxl.setGoalPosition(DXL_ID, goal_position[direction]);
      timer = millis();
      break;
    }
  }

  if(direction >= 1) {
    direction = 0;
  } else {
    direction = 1;
  }

  

  
}

Wait a minute! Are you using XL-320 as your post title indicated or are you using some other actuators? Please reconfirm.

I use XL-320 as per the post title. I follow the suggestion from the dxl class in DynamixelShield library as shown in this following figure. Is it wrong? Please let me know if I did anything wrong. Thank you in advance!
image

The example in the DXL library is just that: an example. You have to adapt it to your particular actuator by reading carefully the information Robotis gives you - see the previous link I gave you.

1/18/2024
@eka123
To wrap up this topic, below is an example sketch showing how to set various data types for P GAIN of an XL-320 and how to do SYNC WRITE/READ into the Shoulder Joints/Actuators for a MINI Robot. The Right Shoulder is set to a P-Gain of 10, while the Left Shoulder is set to a P-Gain of 80. The resulting effect is that the right arm is “slower” than the left arm (see video below):

The complete sketch is listed below:

/* USING DEPRECATED DATA STRUCTURES FOR SYNC WRITE/READ
 * P_control_demo.ino - works on an OpenRB-150.
 * FOR TESTING WITH MINI (XL-320)
 * Copyrights (C) 2024 CNT Robotics LLC
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 *     http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 * 
 *******************************************************************************/
#include <Dynamixel2Arduino.h>
#define DXL_SERIAL   Serial1
const uint8_t BROADCAST_ID = 254;
const float DYNAMIXEL_PROTOCOL_VERSION = 2.0;
const uint8_t GP_DXL_ID_CNT = 2;
const uint8_t GP_DXL_ID_LIST[GP_DXL_ID_CNT] = {1, 2};  // servos set in Position Control mode
const uint8_t GP_DXL_P_GAIN[GP_DXL_ID_CNT] = {10, 80};  // P Gain values used
const uint16_t ADDR_X_PRESENT_POSITION = 37;  // FOR TESTING WITH MINI (XL-320)
const uint16_t LEN_X_PRESENT_POSITION = 2;
const uint16_t ADDR_X_GOAL_POSITION = 30;
const uint16_t LEN_X_GOAL_POSITION = 2;
int16_t goal_position[GP_DXL_ID_CNT] = {512, 512}; // FOR TESTING WITH MINI (XL-320)
int16_t present_position[GP_DXL_ID_CNT] = { 0 }; 
ParamForSyncWriteInst_t GP_sync_write_param; // Parameters structure for SW Goal Position packet
ParamForSyncReadInst_t PP_sync_read_param;  // Parameters structure for SR Present Position packet
RecvInfoFromStatusInst_t PP_read_result;  // Structure for results of SR Present Position command
Dynamixel2Arduino dxl(DXL_SERIAL);
using namespace ControlTableItem;

void setup() {
  Serial.begin(115200);
  while(!Serial);
  Serial.println("Initial Setup & Test");
  dxl.begin(1000000);
  dxl.setPortProtocolVersion(DYNAMIXEL_PROTOCOL_VERSION);
// Preparing for Goal Position SW Packet
  GP_sync_write_param.addr = ADDR_X_GOAL_POSITION; //Goal Position of DYNAMIXEL-X series
  GP_sync_write_param.length = LEN_X_GOAL_POSITION;
  GP_sync_write_param.id_count = GP_DXL_ID_CNT;  // Number of servos in Position Control Mode
  for(int i = 0; i < GP_DXL_ID_CNT; i++){
    GP_sync_write_param.xel[i].id = GP_DXL_ID_LIST[i];
  }
// Preparing for Present Position SR Packet
  PP_sync_read_param.addr = ADDR_X_PRESENT_POSITION; //Present Position of DYNAMIXEL-X series
  PP_sync_read_param.length = LEN_X_PRESENT_POSITION;
  PP_sync_read_param.id_count = GP_DXL_ID_CNT;  // Number of servos in Position Control Mode
  for(int i = 0; i < GP_DXL_ID_CNT; i++){
    PP_sync_read_param.xel[i].id = GP_DXL_ID_LIST[i];
  }
// Setting GP servos into Position Control mode & Setting P Gains
  for(int i = 0; i < GP_DXL_ID_CNT; i++){
    dxl.torqueOff(GP_DXL_ID_LIST[i]);
    dxl.setOperatingMode(GP_DXL_ID_LIST[i], OP_POSITION);
    dxl.writeControlTableItem(P_GAIN, GP_DXL_ID_LIST[i], GP_DXL_P_GAIN[i]); // Setting P gains
    dxl.writeControlTableItem(MOVING_SPEED, GP_DXL_ID_LIST[i], 255); // Setting Moving Speeds
  }
  dxl.torqueOn(BROADCAST_ID);
  // Update actual Goal Position data with Init Values (512) - XL-320
  for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(GP_sync_write_param.xel[i].data, &goal_position[i], sizeof(goal_position[i]));
  }
  dxl.syncWrite(GP_sync_write_param);   // send GP SW Packet
  delay(125);  // minimum needed before issuing a SyncRead command AFTER a SyncWrite command
  // Read in Present Position data
  dxl.syncRead(PP_sync_read_param, PP_read_result);
  Serial.println("======= INIT Sync Read PP (512) =======");
   for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(&present_position[i], &PP_read_result.xel[i].data, PP_read_result.xel[i].length);
    Serial.print("ID: ");Serial.print(PP_read_result.xel[i].id);Serial.print(" ");
    Serial.print(", Present Position: ");Serial.print(present_position[i]);Serial.print(" ");
    Serial.print(", Packet Error: ");Serial.print(PP_read_result.xel[i].error);Serial.print(" ");
    Serial.print(", Param Length: ");Serial.print(PP_read_result.xel[i].length);Serial.print(" ");
    Serial.println();
  }
  Serial.println("END of Initial Setup & Test");
  delay(5000);  // delay 5s
}   // end of setup()

void loop() {
  Serial.println("P Gains Test [10,80]");
  goal_position[0] = (uint16_t) 912;  // DXL 1 P_gain=10 - Slow Right arm
  goal_position[1] = (uint16_t) 112;  // DXL 2 P_gain=80 - Fast Left arm
  // Update actual goal position data with new values
  for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(GP_sync_write_param.xel[i].data, &goal_position[i], sizeof(goal_position[i]));
  }
  dxl.syncWrite(GP_sync_write_param);   // send GP SW Packet
  delay(1000);  
  // Read in Present Position data
  dxl.syncRead(PP_sync_read_param, PP_read_result);
  Serial.println("======= P GAIN TEST Sync Read PP (A) =======");
   for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(&present_position[i], &PP_read_result.xel[i].data, PP_read_result.xel[i].length);
    Serial.print("ID: ");Serial.print(PP_read_result.xel[i].id);Serial.print(" ");
    Serial.print(", Present Position: ");Serial.print(present_position[i]);Serial.print(" ");
    Serial.print(", Packet Error: ");Serial.print(PP_read_result.xel[i].error);Serial.print(" ");
    Serial.print(", Param Length: ");Serial.print(PP_read_result.xel[i].length);Serial.print(" ");
    Serial.println();
   }
  delay(2000);  

  goal_position[0] = (uint16_t) 512;  // DXL 1
  goal_position[1] = (uint16_t) 512;  // DXL 2
  for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(GP_sync_write_param.xel[i].data, &goal_position[i], sizeof(goal_position[i]));
  }
  dxl.syncWrite(GP_sync_write_param);   // send GP SW Packet
  delay(1000);  
  // Read in Present Position data
  dxl.syncRead(PP_sync_read_param, PP_read_result);
  Serial.println("======= P GAIN TEST Sync Read PP (B) =======");
   for(int i=0; i<GP_DXL_ID_CNT; i++){
    memcpy(&present_position[i], &PP_read_result.xel[i].data, PP_read_result.xel[i].length);
    Serial.print("ID: ");Serial.print(PP_read_result.xel[i].id);Serial.print(" ");
    Serial.print(", Present Position: ");Serial.print(present_position[i]);Serial.print(" ");
    Serial.print(", Packet Error: ");Serial.print(PP_read_result.xel[i].error);Serial.print(" ");
    Serial.print(", Param Length: ");Serial.print(PP_read_result.xel[i].length);Serial.print(" ");
    Serial.println();
   }
  delay(2000);  
}   // end of loop()

ONE LAST IMPORTANT POINT that I missed all this time is that you did not set the MOVING_SPEED parameter for the XL-320s to some other values than the default “0” value, which means that the XL-320 is set for its MAX RPM at all times - essentially negating all the effects of different PID values. See excerpt from the e-manual below:

image

1 Like

Hello there! Thank you so much for your clear explanation, it helps me a lot. Have a good day.

Regards,
Eka