Pre-use Preparation

Before using the sample functions, please ensure that the following hardware and environment are complete:

  • Hardware

    • MyCobot Pro 450 robot arm
    • Network cable (for connecting the robot arm to the computer)
    • Power adapter
    • Emergency stop switch (for safe operation)
  • Software and Environment

    • Python 3.6 or later installed. Please refer to the section on Python Environment Setup.
    • The pymycobot library installed (using the pip install pymycobot terminal command)
    • Ensure that the MyCobot Pro 450 is properly powered on and in standby mode.
    • Note: The Pro 450 server automatically starts upon powering on; no manual operation is required.
  • Network Configuration

    • MyCobot Pro 450 default IP address: 192.168.0.232
    • Default port number: 4500
    • Note: PC The local network card IP address must be set to the same network segment as the robot (e.g., 192.168.0.xxx, where xxx is a number between 2 and 254 and must not conflict with the robot).
    • For detailed configuration instructions, please refer to the section on Static IP Configuration.
    • Example:

      • Robot IP: 192.168.0.232
      • PC IP: 192.168.0.100
      • Subnet mask: 255.255.255.0
      • DNS server: 114.114.114.114
    • Verification: After completing the network configuration, execute the following command on the PC terminal. If data packets are successfully returned, the network connection is normal:

      ping 192.168.0.232
      

Joint Zero-Point Calibration

Function Description

This example is used to perform joint zero-point calibration on the Pro 450 robotic arm.

Zero-point calibration affects the accuracy of all subsequent movements; please strictly follow the steps.


Safety Instructions Before Operation

  • All joints will relax during zero-point calibration.

  • The robotic arm may suddenly drop due to gravity.

  • Please make sure to hold the robotic arm firmly with both hands.

  • Ensure there are no people/obstacles nearby.


Step 1: Create a Zero-Point Calibration Script

Create a new file set_joint_zero.py and write the following code:

import time
from pymycobot import Pro450Client

def safe_input(prompt):
    """Safe yes/no input"""
    while True:
        ans = input(prompt + " (yes/no): ").strip().lower()
        if ans in ('y', 'yes'):
            return True
        elif ans in ('n', 'no'):
            return False
        else:
            print("Please enter y/yes or n/no")

def read_angles(pro450, retry=3, delay=0.2):
    """Safely read joint angles"""
    for _ in range(retry):
        angles = pro450.get_angles()
        if isinstance(angles, list):
            return angles
        time.sleep(delay)
    return None

def check_zero_position(angles, tolerance=0.5):
    """Check if the angle is close to zero."""
    if angles is None:
        return False, None
    ok = all(abs(a) <= tolerance for a in angles)
    off_joints = [f"J{i+1}:{round(a,2)}°" for i,a in enumerate(angles) if abs(a) > tolerance]
    return ok, off_joints

def main():
    pro450 = Pro450Client('192.168.0.232', 4500)

    # Power-on check
    if pro450.is_power_on() != 1:
        print("The robot is not powered on, it is being powered on....")
        pro450.power_on()
        time.sleep(0.02)

    if safe_input("The robotic arm is about to relax all joints. Please hold on tight! Type "yes" and press Enter to select "Relax All Joints Now"."):
        pro450.set_motor_enabled(254, 0)
        time.sleep(0.02)
    else:
        print("Zero-point calibration has been cancelled.")
        return

    if safe_input("Please manually drag each joint to the zero mark, type "yes" and press Enter to "Lock the joints and perform zero-point calibration"."):
        pro450.set_motor_enabled(254, 1)
        time.sleep(0.02)
        # Perform joint zero-position calibration
        for i in range(1, 7):
            pro450.set_servo_calibration(i)
            time.sleep(0.05)

        # Calibration complete, reading angle
        angles = read_angles(pro450)
        ok, off_joints = check_zero_position(angles)

        if ok:
            print("✅ Zero-position calibration successful. Current angle:{}".format([round(a, 2) for a in angles]))
        else:
            print(f"⚠️ Zero-position calibration failed; the following joints deviated from zero:{off_joints}")
    else:
        print("The joint has been locked, but zero-position calibration has not been performed.")
        pro450.set_motor_enabled(254, 1)
        time.sleep(0.02)

if __name__ == "__main__":
    try:
        main()
    except Exception as e:
        print(f"❌ Script execution exception: {e}")

Step 2: Run the Script

Execute the following in the terminal:

python3 set_joint_zero.py

Step 3: Relax the Joints

The program will prompt:

All joints are about to be relaxed. Please hold the robotic arm firmly! Type yes and press Enter to immediately relax all joints (yes/no):
  • Confirm the robotic arm is stable

  • Type yes and press Enter

Step 4: Zero-Point Calibration

  • Manually drag each joint

  • Align with the zero-point scale line on the robotic arm

  • Keep the robotic arm stable

The program will prompt:

Please manually drag each joint to the zero-point scale line. Type yes and press Enter to lock the joints and perform zero-point calibration (yes/no):

After typing yes, the system will automatically complete the calibration.

Step 4: Calibration Verification

If the terminal outputs:


✅ Zero-point calibration successful, current angle: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

This indicates calibration is complete.

If a warning message is output, please re-perform the calibration.


← 上一页 | 下一页 →

results matching ""

    No results matching ""