Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

6.1.5: update exception #46

Open
wants to merge 1 commit into
base: gitbook-en
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
91 changes: 77 additions & 14 deletions 6-SDKDevelopment/6.1-Python/6.1.5-ExceptionHandling.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,75 @@
## Robotic Arm Exception Handling Methods

When the robotic arm fails to execute a motion command successfully, corresponding error information can be queried in the Python terminal, for example:
# Robot Arm Exception Inspection and Handling Methods

## 1.Motion Exceptions
When the robot arm fails to execute motion commands successfully, corresponding exception information can be queried in the Python terminal:<br/>

### Controlling the Robotic Arm to an Out-of-Range Position
## 1 Check Robot Status

### 1.1 Status Feedback Analysis

Normally, this interface returns all zeros, indicating no issues. The robot status can be read, with feedback differing between the left and right arms, as detailed below:<br/>

#### Read Robot Status
***
m.get_robot_status() # Read robot status

#### Status Explanation
`[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0]` means:<br/>
The robot is not moving, with no joint limit violations, hardware errors, or software errors.<br/>

Each value corresponds to the following explanation:<br/>
`[Reserved, Movement Status, J1 Limit Violation, J2 Limit Violation, J3 Limit Violation, J4 Limit Violation, J5 Limit Violation, J6 Limit Violation, J7 Limit Violation, J1 Hardware Error, J2 Hardware Error, J3 Hardware Error, J4 Hardware Error, J5 Hardware Error, J6 Hardware Error, J7 Hardware Error, J1 Software Error, J2 Software Error, J3 Software Error, J4 Software Error, J5 Software Error, J6 Software Error, J7 Software Error]`

**Examples:**<br/>
`[0,1,0,0,0,0,0,0,0,0,0,0,3,0,0,0,0,0,0,0,0,0,0]` represents:<br/>
The robot encountered a control error on J4 while moving.:<br/>

`[0,0,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0]` represents::<br/>
Robot J2 overlimit:<br/>

`[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,3,0,0]` represents::<br/>
Robot J5 circuit anomaly - reception error:<br/>

### 1.2 Error Resolution
#### Joint Overlimit
When a joint exceeds its limit, one of the following methods can be used to resolve it:<br/>
##### Perform overlimit return to zero:
The robot will return to the origin at a slower speed.<br/>
****
m.over_limit_return_zero()
##### Release the joint and manually move it back within the limit:

****
m.release_all_servo()
#### Joint Hardware Error
Most hardware errors can be recovered using an exception recovery method:<br/>
****
m.servo_restore(ID)
If the issue persists after using exception recovery or rebooting the robot, please contact our engineers. For detailed joint hardware errors, refer to Figure 1:<br/>
<img src="../../resources/6-SDKDevelopment/6.1-Python/6.1.5/6-1-5-1.2-001.png" alt="pic" width="500" height="400"/><br/>

#### Joint Software Error
Software errors mainly include: circuit anomalies, CAN module anomalies, encoder anomalies, loss of enable, etc.<br/>

When there is a loss of enable, use the following to re-enable the servo before continuing movement:<br/>
****
m.focus_all_servo()
For other anomalies, please contact our engineers. Detailed joint software errors can be found in Figures 2 and 3:<br/>
<img src="../../resources/6-SDKDevelopment/6.1-Python/6.1.5/6-1-5-1.2-002.png" alt="pic" width="500" height="400"/>
<img src="../../resources/6-SDKDevelopment/6.1-Python/6.1.5/6-1-5-1.2-003.png" alt="pic" width="500" height="400"/>

#### Robot in Motion State, but Unable to Move

If the robot is in a motion state and does not respond to new motion commands, first stop the robot's motion:<br/>
***
m.stop()
m.resume()
If the robot still cannot move, please contact our engineers.<br/>

## 2 Check the feedback of executing motion commands

### 2.1 Motion Exceptions

#### Controlling the Robotic Arm to an Out-of-Range Position
form pymycobot import Mercury
m = Mercury('/dev/ttyAMA1')

Expand All @@ -15,10 +80,10 @@ At this point, the robotic arm will stop at the limit position and display the f

**Error: Joint 1 is close to the limit, current angle is 45.535, angle range: -165.0 ~ 45.0**

#### Solution: Avoid software limit by following the indicated angle range.
##### Solution: Avoid software limit by following the indicated angle range.
****

### Cartesian Motion
#### Cartesian Motion

m.send_angles([0.0, 0.0, 0.0, -90.0, 0.0, 89.999, 0.0], 10) # Move the robotic arm to the initial posture

Expand All @@ -28,9 +93,7 @@ At this point, the robotic arm stops mid-motion and displays the following messa

**Error: Joint 2 is close to the limit, current angle is -49.967, angle range: -50.0 ~ 120.0**



#### Solution: Avoid software limit by following the indicated angle range.
##### Solution: Avoid software limit by following the indicated angle range.
****

m.send_coord(3,500,10) # Move the robotic arm to the coordinate position z = 500
Expand All @@ -39,7 +102,7 @@ At this point, the robotic arm stops mid-motion and displays the following messa

**Error: No adjacent solution for linear motion. Check if the arm span is near the limit. Current arm span is 370, maximum arm span is 440 **

#### Solution: Retract the robotic arm.
##### Solution: Retract the robotic arm.

****
m.send_angles([0.0, 0.0, 0.0, -90.0, 0.0, 0, 0.0], 10) # Change initial posture
Expand All @@ -49,7 +112,7 @@ At this point, the robotic arm does not respond to the command and displays the

**Error: Singular position, no solution found. Use send_angles() method to leave this position. Singularity detected at joint 6: 0.0 degrees**

#### Solution: Move out of the singular position as instructed.
##### Solution: Move out of the singular position as instructed.
****

m.send_angle(6,90,10) # Use joint motion to move out of the singular position
Expand All @@ -59,10 +122,10 @@ At this point, the robotic arm does not respond to the command and displays the

**Error: Sent coordinate data is out of range**

#### Solution: Send coordinate values within the limit.
##### Solution: Send coordinate values within the limit.
****

## 2.Motor Exceptions
### 2.2 Motor Exceptions

In firmware version V1.0, when a motor exception occurs, the robotic arm does not respond to motion commands, and corresponding error codes are displayed in the terminal, such as:

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.