|
| ForceSensorCalibResult | arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| | Force sensor calibration algorithm (three-point calibration method)
|
| ForceSensorCalibResultWithError | arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor2 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| | Force sensor calibration algorithm (three-point calibration method)
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor3 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses, const double &mass, const std::vector< double > &cog) |
| | Force sensor offset calibration algorithm
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentify (const std::string &data_file_no_payload, const std::string &data_file_with_payload) |
| | Payload identification algorithm interface based on current
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentify1 (const std::string &file_name) |
| | New version of payload identification algorithm interface based on current
|
| int | arcs::common_interface::RobotAlgorithm::payloadCalculateFinished () |
| | Whether payload identification calculation is finished
|
| Payload | arcs::common_interface::RobotAlgorithm::getPayloadIdentifyResult () |
| | Get the result of payload identification
|
| bool | arcs::common_interface::RobotAlgorithm::frictionModelIdentify (const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &qdd, const std::vector< std::vector< double > > &temp) |
| | Joint friction model identification algorithm interface
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::calibWorkpieceCoordinatePara (const std::vector< std::vector< double > > &q, int type) |
| | Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling) Input multiple sets of joint angles and calibration type, output workpiece coordinate pose (relative to robot base)
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardDynamics (const std::vector< double > &q, const std::vector< double > &torqs) |
| | Forward dynamics
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardDynamics1 (const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset) |
| | Forward dynamics based on the given TCP offset
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardKinematics (const std::vector< double > &q) |
| | Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output TCP pose
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardKinematics1 (const std::vector< double > &q, const std::vector< double > &tcp_offset) |
| | Forward kinematics Input joint angles, output TCP pose
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardToolKinematics (const std::vector< double > &q) |
| | Forward kinematics (ignoring TCP offset)
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::forwardKinematicsAll (const std::vector< double > &q) |
| | Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output links poses
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseKinematics (const std::vector< double > &qnear, const std::vector< double > &pose) |
| | Inverse kinematics Input TCP pose and reference joint angles, output joint angles
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseKinematics1 (const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset) |
| | Inverse kinematics Input TCP pose and reference joint angles, output joint angles
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseKinematicsAll (const std::vector< double > &pose) |
| | Solve all inverse kinematics solutions based on the activated TCP offset
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseKinematicsAll1 (const std::vector< double > &pose, const std::vector< double > &tcp_offset) |
| | Solve all inverse kinematics solutions based on the provided TCP offset
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseToolKinematics (const std::vector< double > &qnear, const std::vector< double > &pose) |
| | Inverse kinematics (ignoring TCP offset)
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseToolKinematicsAll (const std::vector< double > &pose) |
| | Inverse kinematics (ignoring TCP offset)
|
| ResultWithErrno3 | arcs::common_interface::RobotAlgorithm::getRobotConfiguration (const std::vector< double > &q) |
| | Calculate and return the corresponding robot configuration based on input joint angles
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::calcJacobian (const std::vector< double > &q, bool base_or_end) |
| | Calculate the Jacobian matrix at the robot end-effector
|
| std::vector< std::vector< double > > | arcs::common_interface::RobotAlgorithm::pathBlend3Points (int type, const std::vector< double > &q_start, const std::vector< double > &q_via, const std::vector< double > &q_to, double r, double d) |
| | Solve the blended trajectory points
|
| int | arcs::common_interface::RobotAlgorithm::generatePayloadIdentifyTraj (const std::string &name, const TrajConfig &traj_conf) |
| | Generate excitation trajectory for payload identification This interface internally calls pathBufferAppend The offline trajectory is stored in the buffer, and can be executed later via movePathBuffer
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentifyTrajGenFinished () |
| | Whether payload identification trajectory generation is finished
|
| std::vector< std::vector< double > > | arcs::common_interface::RobotAlgorithm::pathMoveS (const std::vector< std::vector< double > > &qs, double d) |
| | Solve the trajectory points for moveS
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::calibVibrationParams (const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &target_q, const std::vector< std::vector< double > > &target_qd, const std::vector< std::vector< double > > &target_qdd, const std::vector< double > &tool_offset) |
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::calibVibrationParams1 (const std::string &record_cache_name, const std::vector< double > &tool_offset) |
| int | arcs::common_interface::RobotAlgorithm::needVibrationRecalib (const VibrationRecalibrationParameter ¶m1, const VibrationRecalibrationParameter ¶m2, double threshold) |
| int | arcs::common_interface::RobotAlgorithm::addCollisionBox (const std::string &name, const std::string &link_name, const std::vector< std::vector< double > > &sizes, const std::vector< std::vector< double > > &poses) |
| | Add a box collision object
|
| int | arcs::common_interface::RobotAlgorithm::removeCollisionObject (const std::string &name) |
| | Remove a collision object by name
|
| int | arcs::common_interface::RobotAlgorithm::validatePath (int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d, bool check_external_collision=false) |
| | Validate the reachability of the robot's motion path from start point to end point
|
Interfaces related to robot algorithms
| int arcs::common_interface::RobotAlgorithm::addCollisionBox |
( |
const std::string & | name, |
|
|
const std::string & | link_name, |
|
|
const std::vector< std::vector< double > > & | sizes, |
|
|
const std::vector< std::vector< double > > & | poses ) |
Add a box collision object
This interface adds a named group of box collision objects into the current robot algorithm scene.
- Parameters
-
| name | Unique identifier of the collision object |
| link_name | Name of the reference link the collision object is attached to. Common names include: world, base_link, shoulder_Link, upperArm_Link, foreArm_Link, wrist1_Link, wrist2_Link, wrist3_Link, and end_effector |
| sizes | List of box sizes. Each element is in the format [length, width, height], unit: m |
| poses | List of collision object poses. Each element is a pose relative to the reference link in the format [x, y, z, rx, ry, rz] |
- Returns
- 0 on success, non-zero on failure
- Lua function prototype
- addCollisionBox(name, link_name, sizes, poses) -> integer
- Lua example
- – Add an environment collision box attached to world addCollisionBox("env_box", "world", {{0.4, 0.4, 0.2}}, {{0.6, 0.0, 0.1, 0.0, 0.0, 0.0}})
– Add a tool collision box attached to end_effector addCollisionBox("tool_box", "end_effector", {{0.1, 0.08, 0.06}}, {{0.0, 0.0, 0.05, 0.0, 0.0, 0.0}})
- Python function prototype
- addCollisionBox(name: str, link_name: str, sizes: list[list[float]],
poses: list[list[float]]) -> int
- Python example
Add an environment collision box attached to world
robot_algorithm.addCollisionBox( "env_box", "world", [[0.4, 0.4, 0.2]], [[0.6, 0.0, 0.1, 0.0, 0.0, 0.0]] )
Add a tool collision box attached to end_effector
robot_algorithm.addCollisionBox( "tool_box", "end_effector", [[0.1, 0.08, 0.06]], [[0.0, 0.0, 0.05, 0.0, 0.0, 0.0]] )
- JSON-RPC request example
- {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.addCollisionBox", "params":["env_box","world",[[0.4,0.4,0.2]], [[0.6,0.0,0.1,0.0,0.0,0.0]]],"id":1}
- JSON-RPC response example
- {"id":1,"jsonrpc":"2.0","result":0}
| int arcs::common_interface::RobotAlgorithm::validatePath |
( |
int | type, |
|
|
const std::vector< double > & | start, |
|
|
double | r1, |
|
|
const std::vector< double > & | end, |
|
|
double | r2, |
|
|
double | d, |
|
|
bool | check_external_collision = false ) |
Validate the reachability of the robot's motion path from start point to end point
This interface verifies whether the specified path has unreachable conditions such as out-of-limit, self-collision, collision with external objects, singularity, etc., by sampling. It supports two path type validations: Joint-Joint and Pose-Pose.
- Parameters
-
| type | Path type identifier, specifying the data type of start and end points: 0 - Start: Joint angles, End: Joint angles 1 - Start: Pose, End: Pose |
| start | Start point data of the path |
| r1 | Start point blending radius, unit: m (meters), used to smooth path sampling near the start point |
| end | End point data of the path, format is consistent with start (matching the type specified by type) |
| r2 | End point blending radius, unit: m (meters), used to smooth path sampling near the end point |
| d | Path sampling interval, unit: m (meters). Smaller intervals improve verification accuracy but increase time consumption |
| check_external_collision | Whether to enable external collision checks: false - Keep the original reachability and self-collision checks true - Add collision checks against external objects on top of the original logic |
- Returns
- Path reachability result code: 0 - Reachable: Path is normal, movement is possible -18 - Joint/ Cartesian space limits exceeded in the path -21 - Trajectory generation failed -22 - Self-collision of the robot body in the path -24 - Path passing through robot singular configuration -27 - The target point has a solution but exceeds joint limits configuration
- Exceptions
-
- Lua function prototype
- validatePath(type, start, r1, end, r2, d, check_external_collision) -> integer
- Lua example
- – Validate reachability of Joint-Joint path for 6-axis robot and enable – external collision checks local start_joint = {0.0, 0.0, 90.0, 0.0, 90.0, 0.0} local end_joint = {30.0, 0.0, 90.0, 0.0, 90.0, 0.0} result = validatePath(0, start_joint, 0.01, end_joint, 0.01, 0.05, true)
- Python function prototype
- validatePath(type: int, start: list[float], r1: float, end: list[float], r2: float, d: float, check_external_collision: bool = False) -> int
- Python example
Validate reachability of Joint-Pose path for 6-axis robot and enable
external collision checks
start_joint = [0.0, 0.0, math.pi/2, 0.0, math.pi/2, 0.0] end_pose = [0.5, 0.2, 0.8, 0.0, math.pi/2, 0.0] result = validatePath(1, start_joint, 0.01, end_pose, 0.01, 0.005, True)
- JSON-RPC request example
- {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.validatePath","params":[0, [0.0,0.0,1.57,0.0,1.57,0.0], 0.01, [0.52,0.0,1.57,0.0,1.57,0.0], 0.01, 0.005, true],"id":1}
- JSON-RPC response example {"id":1,"jsonrpc":"2.0","result":0}