neurapy_ai_utils.robot package
neurapy_ai_utils.robot.kinematics_interface module
- class neurapy_ai_utils.robot.kinematics_interface.DummyKinematics(num_joints: int = 7)
Bases:
KinematicsInterface- cartesian_2_joint(pose, reference_joint_states=None)
- execute(ids: List[int], execution_feasibilities: List[bool])
- get_current_joint_state() List[float]
- move_joint_to_cartesian(goal_pose, speed=None, acc=None)
- move_joint_to_joint(pose_joint, speed=None, acc=None)
- move_joint_via_points(trajectory, speed=None, acc=None)
- move_linear(goal_pose, speed=None, acc=None)
- move_linear_via_points(trajectory, speed=None, acc=None)
- plan_motion_joint_to_cartesian(goal_pose, reference_joint_states=None, start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[bool, int, List[float]]
- plan_motion_joint_to_joint(goal_pose: List[float], start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[bool, int, List[float]]
- plan_motion_joint_via_points(trajectory: List[List[float]], start_joint_states: List[float] | None = None, speed: float | None = None, acc: float | None = None, reusable=False) Tuple[bool, int, List[float]]
- plan_motion_linear(goal_pose: List[float], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[bool, int, List[float]]
- plan_motion_linear_via_points(goal_poses: List[List[float]], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed=None, acc=None, rot_speed=None, rot_acc=None, blending_radius=None, reusable=False) Tuple[bool, int, List[float]]
- set_motion_param(speed_mj: float, speed_ml: float, acc_mj: float, acc_ml: float)
- wait(time_s)
- class neurapy_ai_utils.robot.kinematics_interface.KinematicsInterface
Bases:
ABC- abstract cartesian_2_joint(pose, reference_joint_states=None)
- abstract change_gripper_to(end_effector: EndEffector)
- abstract clear_ids(ids: List[int]) bool
- abstract execute(ids: List[int], execution_feasibilities: List[bool])
- abstract finish() None
- abstract get_current_cartesian_tcp_pose() List[float]
- abstract get_current_joint_state() List[float]
- abstract move_joint_to_cartesian(goal_pose, speed=None, acc=None)
- abstract move_joint_to_joint(pose_joint, speed=None, acc=None)
- abstract move_joint_via_points(trajectory, speed=None, acc=None)
- abstract move_linear(goal_pose, speed=None, acc=None)
- abstract move_linear_via_points(goal_poses, speed=None, acc=None, rot_speed=None, rot_acc=None, blending_radius=None)
- abstract plan_motion_joint_to_cartesian(goal_pose, reference_joint_states=None, start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[Tuple[bool, bool], int, List[float]]
- abstract plan_motion_joint_to_joint(goal_pose: List[float], start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[Tuple[bool, bool], int, List[float]]
- abstract plan_motion_joint_via_points(trajectory: List[List[float]], start_joint_states: List[float] | None = None, speed: int | None = None, acc: int | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
- abstract plan_motion_linear(goal_pose: List[float], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed=None, acc=None, reusable=False) Tuple[Tuple[bool, bool], int, List[float]]
- abstract plan_motion_linear_via_points(goal_poses: List[List[float]], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed: float | None = None, acc: float | None = None, rot_speed: float | None = None, rot_acc: float | None = None, blending_radius: float | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
- abstract set_motion_param(speed_mj: float, speed_ml: float, acc_mj: float, acc_ml: float)
- abstract set_motion_till_force(stopping_forces: List[float], reflex_mode_after_contact: bool) None
- abstract wait(time_s)
neurapy_ai_utils.robot.maira_kinematics module
neurapy_ai_utils.robot.moveit_kinematics module
- class neurapy_ai_utils.robot.moveit_kinematics.MoveitKinematics
Bases:
KinematicsInterface- cartesian_2_joint(goal_pose_cartesian: List[float], reference_joint_states: List[float] | None = None) List[float]
Get the inverse kinematics for a given pose and current joint state
- Parameters:
goal_pose_cartesian (List[float]) – Cartesian pose of tcp frame
reference_joint_states (Optional[List[float]], optional) – Joint positions to seed IK solver. Default is None, to use current joint positions.
- Returns:
Joint position from IK solution.
- Return type:
List[float]
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- change_gripper_to(end_effector: EndEffector) None
Choose gripper to control.
- Parameters:
end_effector (neurapy_ai.utils.types.EndEffector) – End effector parameters as saved on database.
- clear_ids(ids: List[int]) bool
Clear given plan IDs from memory stack to prevent overload.
- Parameters:
ids (List[int]) – Plan IDs
- Returns:
Clearing success
- Return type:
bool
- execute(ids: List[int], execution_feasibilities: List[bool]) None
Execute a given plan.
- Parameters:
ids (List[int]) – A list of id of the planned motion to be executed
execution_feasibilities (List[bool]) – A List of flag indicate the execution feasibility, false will be jumped over
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- finish() None
- get_current_cartesian_tcp_pose() List[float]
Get the current tcp pose as a list of floats
- Returns:
Current tcp pose
- Return type:
List[float]
- get_current_joint_state() List[float]
Get the current joint state as a list of floats
- Returns:
Current joint positions
- Return type:
List[float]
- move_joint_to_cartesian(goal_pose: List[float], reference_joint_states: List[float] | None = None, speed: int | None = None, acc: int | None = None) bool
Execute move joint action with given goal, speed and acceleration
- Parameters:
goal_pose (list) – TCP goal pose in cartesian as a list
reference_joint_states (Union[List[float],None]) – Reference joint states to seed the IK solution for the given pose. Defaults to None, to use the current joint positions.
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
- Returns:
Move command success
- Return type:
bool
- Raises:
TypeError – If get wrong input type
RuntimeError – If action failed
- move_joint_to_joint(pose_joint: List[float], speed: int | None = None, acc: int | None = None) bool
Execute move joint action with given goal, speed and acceleration
- Parameters:
pose_joint (list[float]) – Goal joint positions
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
- Returns:
Move command success
- Return type:
bool
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- move_joint_via_points(trajectory: List[List[float]], speed: int | None = None, acc: int | None = None) bool
Execute move joint via points action with given joint trajectory, speed and acceleration
- Parameters:
trajectory (List[List[float]]) – Joint trajectory
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
- Returns:
Move command success
- Return type:
bool
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- move_linear(goal_pose: List[float], speed: float | None = None, acc: float | None = None, rot_speed: float | None = None, rot_acc: float | None = None) bool
Execute move linear action with given goal, speed and acceleration
- Parameters:
goal_pose (list) – TCP goal pose in cartesian as a list
speed (Optional[float], optional) – Translation speed in m/sec. Defaults to None, to use the class’ default value.
acc (Optional[float], optional) – Translation acceleration in m2/sec. Defaults to None, to use the class’ default value.
rot_speed (Optional[float], optional) – Rotation speed in rad/sec. Defaults to None, to use the class’ default value.
rot_acc (Optional[float], optional) – Rotation acceleration in rad/sec2. Defaults to None, to use the class’ default value.
- Returns:
Move command success
- Return type:
bool
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- move_linear_via_points(goal_poses: List[List[float]], speed: float | None = None, acc: float | None = None, rot_speed: float | None = None, rot_acc: float | None = None, blending_radius: float | None = None) bool
Execute move linear via points action with given goal, speed and acceleration
- Parameters:
goal_poses (list[list[float]]) – TCP goal cartesian poses list
speed (Optional[float], optional) – Translation speed in m/sec. Defaults to None, to use the class’ default value.
acc (Optional[float], optional) – Translation acceleration in m/sec2. Defaults to None, to use the class’ default value.
rot_speed (Optional[float], optional) – Rotational speed in rad/sec. Defaults to None, to use the class’ default value.
rot_acc (Optional[float], optional) – Rotational acceleration in rad/sec2. Defaults to None, to use the class’ default value.
blending_radius (Optional[float], optional) – Blending radius in m. Defaults to None, to use the class’ default value.
- Returns:
Move command success
- Return type:
bool
- Raises:
TypeError – Wrong input type
RuntimeError – Action failed
- plan_motion_joint_to_cartesian(goal_pose: List[float], reference_joint_states: List[float] | None = None, start_joint_states: List[float] | None = None, speed: int | None = None, acc: int | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
Plan motion for move joint action with given goal, speed and acceleration
- Parameters:
goal_pose (list) – TCP goal pose in cartesian as a list
reference_joint_states (Union[List[float],None]) – Reference joint states to seed the IK solution for the given pose. Defaults to None, to use the current joint positions.
start_joint_states (Union[List[float],None]) – Start joint states. Defaults to None, to use the current joint positions.
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
reusable (Optional[bool], optional) – Reuse the planned ID for repeated executions. Defaults to False, the plan will be executable only once.
- Returns:
Tuple consisting of (plan success, plan feasibility), result plan ID that points to planned trajectory, last joint positions in the result trajectory.
- Return type:
Tuple[Tuple[bool,bool], int, List[float]]
- Raises:
TypeError – Wrong input type
RuntimeError – Planning failed
- plan_motion_joint_to_joint(goal_pose: List[float], start_joint_states: List[float] | None = None, speed: int | None = None, acc: int | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
Plan motion for move joint action with given goal, speed and acceleration
- Parameters:
goal_pose (list[float]) – Goal joint positions
start_joint_states (Union[List[float],None]) – Start joint states. Defaults to None, to use the current joint positions.
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
reusable (Optional[bool], optional) – Reuse the planned ID for repeated executions. Defaults to False, the plan will be executable only once.
- Returns:
Tuple consisting of (plan success, plan feasibility), result plan ID that points to planned trajectory, last joint positions in the result trajectory.
- Return type:
Tuple[Tuple[bool,bool], int, List[float]]
- Raises:
TypeError – Wrong input type
RuntimeError – Planning failed
- plan_motion_joint_via_points(trajectory: List[List[float]], start_joint_states: List[float] | None = None, speed: int | None = None, acc: int | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
Plan motion for move joint via points action with given joint trajectory, speed and acceleration
- Parameters:
trajectory (List[List[float]]) – Joint trajectory
start_joint_states (Union[List[float],None]) – Start joint states. Defaults to None, to use the current joint positions.
speed (Optional[int], optional) – Joint speed as percentage value [0, 100]. Defaults to None, to use the class’ default value.
acc (Optional[int], optional) – Joint acceleration as percentage value [0, 100]. Defaults to None, to use the class’ default value.
reusable (Optional[bool], optional) – Reuse the planned ID for repeated executions. Defaults to False, the plan will be executable only once.
- Returns:
Tuple consisting of (plan success, plan feasibility), result plan ID that points to planned trajectory, last joint positions in the result trajectory.
- Return type:
Tuple[Tuple[bool,bool], int, List[float]]
- Raises:
TypeError – Wrong input type
RuntimeError – Planning failed
- plan_motion_linear(goal_pose: List[float], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed: float | None = None, acc: float | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
Plan motion for move linear action with given goal, speed and acceleration
- Parameters:
goal_pose (List[float]) – TCP goal cartesian pose as list
start_cartesian_pose (Union[List[float],None]) – Start tcp cartesian pose relative to the base frame. Defaults to None, to use the current tcp pose.
start_joint_states (Union[List[float],None]) – Start joint states. Defaults to None, to use the current joint positions.
speed (Optional[float], optional) – Translation speed in m/sec. Defaults to None, to use the class’ default value.
acc (Optional[float], optional) – Translation acceleration in m2/sec. Defaults to None, to use the class’ default value.
reusable (Optional[bool], optional) – Reuse the planned ID for repeated executions. Defaults to False, the plan will be executable only once.
- Returns:
Tuple consisting of the plan and fraction.
- Return type:
Tuple[RobotTrajectory,float]
- Raises:
TypeError – Wrong input type
RuntimeError – Planning failed
- plan_motion_linear_via_points(goal_poses: List[List[float]], start_cartesian_pose: List[float] | None = None, start_joint_states: List[float] | None = None, speed: float | None = None, acc: float | None = None, rot_speed: float | None = None, rot_acc: float | None = None, blending_radius: float | None = None, reusable: bool | None = False) Tuple[Tuple[bool, bool], int, List[float]]
Plan motion for move linear via points action with given goal, speed and acceleration.
- Parameters:
goal_poses (list) – TCP goal cartesian poses list
start_cartesian_pose (Union[List[float],None]) – Start tcp cartesian pose relative to the base frame. Defaults to None, to use the current tcp pose.
start_joint_states (Union[List[float],None]) – Start joint states. Defaults to None, to use the current joint positions.
speed (Optional[float], optional) – Translation speed in m/sec. Defaults to None, to use the class’ default value.
acc (Optional[float], optional) – Translation acceleration in m/sec2. Defaults to None, to use the class’ default value.
rot_speed (Optional[float], optional) – Rotational speed in rad/sec. Defaults to None, to use the class’ default value.
rot_acc (Optional[float], optional) – Rotational acceleration in rad/sec2. Defaults to None, to use the class’ default value.
blending_radius (Optional[float], optional) – Blending radius in m. Defaults to None, to use the class’ default value.
reusable (Optional[bool], optional) – Reuse the planned ID for repeated executions. Defaults to False, the plan will be executable only once.
- Returns:
Tuple consisting of (plan success, plan feasibility), result plan ID that points to planned trajectory, last joint positions in the result trajectory.
- Return type:
Tuple[Tuple[bool, bool], int, List[float]]
- Raises:
TypeError – Wrong input type
RuntimeError – Planning failed
- set_motion_param(speed_mj: float, speed_ml: float, acc_mj: float, acc_ml: float) None
Set the default motion speed and acceleration for move joint and move linear.
- Parameters:
speed_mj (float) – Speed for move joint, from 0 - 100
speed_ml (float) – Speed for move linear, m/sec
acc_mj (float) – Acceleration for move joint, from 0 - 100
acc_ml (float) – Acceleration for move linear, m/sec2
- wait(time_s: float) None
Wait for given time in seconds.
- Parameters:
time_s (float) – Waiting time in seconds
- Raises:
RuntimeError: – If action failed