Motion client¶
Important
The version 1.0 of MotionClient is now deprecated and will be removed in a future release. Please use the new MotionClient version 2.0
Overview¶
The main classes to plan and execute trajectories with xamla_motion
are xamla_motion.MoveGroup
and xamla_motion.EndEffector
. The difference between both classes
is the space in which they operate. The xamla_motion.MoveGroup
class plans and
executes trajectories where the input is defined in joint space. Whereas
the xamla_motion.EndEffector
class plans and executes trajectories where the input
is defined in cartesian/task space.
Example:
import asyncio
from pyquaternion import Quaternion
from xamla_motion.data_types import CartesianPath, JointPath, Pose
from xamla_motion.motion_client import EndEffector, MoveGroup
from xamla_motion.utility import register_asyncio_shutdown_handler
# functions for supervised executation
async def next(stepped_motion_client):
while True:
await asyncio.sleep(0.1)
if stepped_motion_client.state:
stepped_motion_client.step()
print('progress {:5.2f} percent'.format(
stepped_motion_client.state.progress))
async def run_supervised(stepped_motion_client):
print('start supervised execution')
task_next = asyncio.ensure_future(next(stepped_motion_client))
await stepped_motion_client.action_done_future
task_next.cancel()
print('finished supervised execution')
def main():
# create move group instance
move_group = MoveGroup()
# get default endeffector of the movegroup
end_effector = move_group.get_end_effector()
# create cartesian path and equivalent joint path
t1 = [0.502522, 0.2580, 0.3670]
q1 = Quaternion(w=0.304389, x=0.5272, y=0.68704, z=0.39666)
t2 = [0.23795, 0.46845, 0.44505]
q2 = Quaternion(w=0.212097, x=0.470916, y=0.720915, z=0.462096)
t3 = [0.6089578, 0.3406782, 0.208865]
q3 = Quaternion(w=0.231852, x=0.33222, y=0.746109, z=0.528387)
pose_1 = Pose(t1, q1)
pose_2 = Pose(t2, q2)
pose_3 = Pose(t3, q3)
cartesian_path = CartesianPath([pose_1, pose_2, pose_3])
joint_path = end_effector.inverse_kinematics_many(cartesian_path,
False).path
loop = asyncio.get_event_loop()
register_asyncio_shutdown_handler(loop)
async def example_moves():
print('test MoveGroup class')
print('---------------- move joints -------------------')
await move_group.move_joints(joint_path)
print('---------------- move joints collision free -------------------')
await move_group.move_joints_collision_free(joint_path)
print('---------------- move joints supervised -------------------')
stepped_motion_client = move_group.move_joints_supervised(
joint_path, 0.5)
await run_supervised(stepped_motion_client)
print('----------------move joints collision free supervised -------------------')
stepped_motion_client = move_group.move_joints_collision_free_supervised(
joint_path, 0.5)
await run_supervised(stepped_motion_client)
print('test EndEffector class')
print('---------------- move poses -------------------')
await end_effector.move_poses(cartesian_path)
print('---------------- move poses collision free -------------------')
await end_effector.move_poses_collision_free(cartesian_path)
print('---------------- move poses supervised -------------------')
stepped_motion_client = end_effector.move_poses_supervised(
cartesian_path, None, 0.5)
await run_supervised(stepped_motion_client)
print('---------------- move poses collision free supervised -------------------')
stepped_motion_client = end_effector.move_poses_collision_free_supervised(
cartesian_path, None, 0.5)
await run_supervised(stepped_motion_client)
try:
loop.run_until_complete(example_moves())
finally:
loop.close()
if __name__ == '__main__':
main()
MoveGroup¶
-
class
xamla_motion.
MoveGroup
(move_group_name=None, end_effector_name=None, motion_service=None)[source]¶ Class with encapsulate move functionality for a specific move group
-
set_default_end_effector
(end_effector_name: str)[source]¶ Set one of the end effector from the list of available ones as default
-
get_end_effector
(name: Union[None, str]) → EndEffector[source]¶ Get the end effector specified by name or the default end effector
-
get_current_joint_states
() → JointStates[source]¶ Returns the current joint states of the move group joints
-
get_current_joint_positions
() → JointValues[source]¶ Returns the current joint positions of the move group joints
-
plan_move_joints(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> Tuple[JointTrajectory, PlanParameters] Plans a trajectory from current state to target joint positions
-
plan_move_joints_collision_free(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> Tuple[JointTrajectory, PlanParameters] Plans a collision free trajectory from current to target joint positions.
-
move_joints(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None)
Asynchronous plan and execute joint trajectory
-
move_joints_supervised(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> SteppedMotionClient Plan joint trajectory and creates a supervised executor Create MoveJointsOperation for target joint positions
-
move_joints_collision_free(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None)
Asynchronous plan and execute collision free joint trajectory
-
move_joints_collision_free_supervised(
target: Union[JointValues, JointPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> SteppedMotionClient Plan collision free joint trajectory and creates a supervised executor
Initialize MoveGroup class
The initialization process is possible with different settings:
- move_group_name and end_effector_name are None:
In this case the first available move group and its first end effector is selected automatically. If no move group or end_effector is available exception is raised.
- move_group_name is defined and end_effector_name is none:
In this case the initialization routine tries to find the move group with requested name. If it is available create a instance for this move group and the first available end effector as default end effector. Else an exceptions is raised.
- move_group is None and end_effector_name is defined:
In this case the initialization routine tries to find the move group with requested end effector. If it is available create a instance for this move group and the requested end effector as default end effector. Else an exceptions is raised.
- move_group is defined and also end_effector_name is defined:
In this case the initialization routine tries to find the requested move group with requested end effector. If it is available create a instance for this move group and the requested end effector as default end effector. Else an exceptions is raised.
- Parameters
move_group_name (Union[None, str]) – If defined name of the move group which this instance should represent
end_effector_name (Union[None, str]) – If defined name of the end_effector which should be used as default end_effector
motion_service (Union[None, MotionService]) – An instance of MotionService which is used to communicate with the motion server if None a new instance of MotionService is created
- Raises
TypeError – If motion_service is not of type MotionService or If the other inputs are not str convertable
ServiceException – If necessary services to query available move groups and end effectors are not available
RuntTimeError – If requested move group or end effector not exist or are not available
-
acceleration_scaling
¶ Current acceleration scaling value
- acceleration_scalingfloat convertable
The acceleration scaling value is the value which was applied to the default accelerations to get the current accelerations limits. The default accelerations are maximal accelerations. The maximal accelerations are provided by the motion server and queried from it during the initialization process.
-
collision_check
¶ bool If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
- Type
collision_check
-
default_plan_parameters
¶ PlanParameters (read only) Instance of PlanParameters from which the limits and settings are used when no specific user input is given
- Type
plan_parameters
-
default_task_space_plan_parameters
¶ TaskSpacePlanParameters (read only) Instance of TaskSpacePlanParameters from which the limits and settings are used when no specific user input is given
- Type
task_space_plan_parameters
-
end_effector_names
¶ List[str] (read only) List of end effectors the move groups contains
- Type
end_effector_names
-
get_current_joint_positions
()[source] Returns the current joint positions of the move group joints
- Returns
joint_positions – current joint position of the move group joints
- Return type
- Raises
ServiceException – If Service is not available or finish not successful
-
get_current_joint_states
()[source] Returns the current joint states of the move group joints
- Returns
joint_states – current joint states of the move group joints
- Return type
- Raises
ServiceException – If Service is not available or finish not successful
-
get_end_effector
(name=None)[source] Get the end effector specified by name or the default end effector if name is not provided
- Parameters
name (str convertable (optinal)) – Name of the end effector which should be returned
- Returns
end_effector – Instance of Class EndEffector with requested name
- Return type
- Raises
RuntimeError – If no end effector exist with the requested name
-
ik_jump_threshold
¶ float convertable maximal allowed inverse kinematics jump threshold
- Type
ik_jump_threshold
-
joint_set
¶ JointSet (read only) joint set of the move group
- Type
joint_set
-
max_deviation
¶ float convertable Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
- Type
max_deviation
-
motion_service
¶ MotionService (read only) return the instance of motion service which is used to communicate via ros which the motion server
- Type
motion_service
-
move_joints
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Asynchronous plan and execute joint trajectory from joint space input
- Parameters
target (Union[JointValues, JointPath]) – Target joint positions or joint path
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_joints_collision_free
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Asynchronous plan and execute collision free joint trajectory from joint space input
- Parameters
target (Union[JointValues, JointPath]) – Target joint positions or joint path
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_joints_collision_free_supervised
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ plan collision free joint trajectory and creates a supervised executor
- Parameters
target (Union[JointValues, JointPath]) – Target joint positions or joint path
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Returns
executor – Executor for supervised execution of trajectory
- Return type
SteppedMotionClient
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_joints_supervised
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plan joint trajectory and creates a supervised executor
- Parameters
target (Union[JointValues, JointPath]) – Target joint positions or joint path
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Returns
executor – Executor for supervised execution of trajectory
- Return type
SteppedMotionClient
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
name
¶ str (read only) move group name
- Type
name
-
plan_move_joints
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plans a trajectory from current state to target joint positions :type target:
Union
[JointValues
,JointPath
] :param target: Target joint positions or target JointPath :type target: Union[JointValues, JointPath] :type velocity_scaling:Union
[None
,float
] :param velocity_scaling: Scaling factor which is applied on the maximalpossible joint velocities
- Parameters
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Returns
trajectory, parameters – Returns a tuple where the first argument is the planed trajectory and the second argument the parameters which are used for it
- Return type
Tuple[JointTrajectory, PlanParameters]
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
plan_move_joints_collision_free
(target, velocity_scaling=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plans a collision free trajectory from current to target joint positions
- Parameters
target (Union[JointValues, JointPath]) – Target joint positions or joint path
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Returns
trajectory, parameters – Returns a tuple where the firt argument is the planed trajectory and the second argument the parameters which are used for it
- Return type
Tuple[JointTrajectory, PlanParameters]
- Raises
TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
sample_resolution
¶ float convertable Trajectory point sampling frequency If value smaller one in seconds else in Hz
- Type
sample_resolution
-
selected_end_effector
¶ str (read only) Name of the currently selected end effector
- Type
selected_end_effector
-
set_default_end_effector
(end_effector_name)[source] set one of the end effector from the list of available ones as default
- Parameters
end_effector_name (str convertable) – Name of the end effector which should be now the default end effector of this move group
- Raises
TypeError – If end_effector_name is not str convertable
RuntimeError – If the input end effector name is not available
-
velocity_scaling
¶ Current velocity scaling value
- velocity_scalingfloat convertable
The velocity scaling value is the value which was applied to the default velocities to get the current velocity limits. The default velocities are maximal velocities. The maximal velocities are provided by the motion server and queried from it during the initialization process.
-
EndEffector¶
-
class
xamla_motion.
EndEffector
(move_group, end_effector_name, end_effector_link_name)[source]¶ Class with encapsulate move functionality for a specific end effector
-
from_end_effector_name
(end_effector_name: str) → EndEffector[source]¶ Creates an instance of MoveGroup and select the correct instance of EndEffector
-
compute_pose
(joint_values: JointValues) → Pose[source]¶ compute pose from joint values / configuration
-
inverse_kinematics(
poses: Union[Pose, CartesianPath], collision_check: Union[None, bool], seed: Union[None, JointValues], timeout: Union[None, datatime.timedelta], const_seed: bool, attempts: int
) -> JointValues: inverse kinematic solutions for one pose
-
inverse_kinematics_many(
poses: Union[Pose, CartesianPath], collision_check: Union[None, bool], seed: Union[None, JointValues], timeout: Union[None, datatime.timedelta], const_seed: bool, attempts: int
) -> IkResults: inverse kinematic solutions for many poses
-
move_poses(
target: Union[Pose, CartesianPath], seed: Union[None, JointValues]=None, velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None)
Asynchronous plan and execute trajectory from task space input
-
move_poses_supervised(
target: Union[Pose, CartesianPath], seed: Union[None, JointValues]=None, velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> SteppedMotionClient Plan trajectory from task space input and create executor
-
move_poses_collision_free(
target: Union[Pose, CartesianPath], seed: Union[None, JointValues]=None, velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None)
Asynchronous plan and execute collision free trajectory from task space input
-
move_poses_collision_free_supervised(
target: Union[Pose, CartesianPath], seed: Union[None, JointValues]=None, velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None
) -> SteppedMotionClient Plan collision free trajectory from task space input and create executor
-
plan_poses_linear(
target: Union[Pose, CartesianPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None, seed: Union[None, JointValues]=None
) -> Tuple[JointTrajectory, PlanParameters] Plans a trajectory with linear movements from task space input
-
move_poses_linear(
target: Union[Pose, CartesianPath], velocity_scaling: Union[None, float]=None, collision_check: Union[None, bool]=None, max_deviation: Union[None, float]=None, acceleration_scaling: Union[None, float]=None)
Plans and executes a trajectory with linear movements from task space input
Initialize EndEffector class
- Parameters
move_group (xamla_motion.MoveGroup) – Instance of move group where the endeffector belongs to
end_effector_name (str_convertable) – If defined name of the end_effector which should for which a instance of EndEffector is created and which is selected as default for the move group
end_effector_link_name (str convertable) – name of the end effector link
- Raises
TypeError – If move_group is not of type MoveGroup or If the other inputs are not str convertable
ServiceException – If necessary services to query available move groups and end effectors are not available
RuntTimeError – If requested move group or end effector not exist or are not available
-
compute_pose
(joint_values)[source] compute pose from joint values / configuration
- Parameters
joint_values (JointValues) – Joint configuration of the robot which should be transformed to a cartesian pose
- Returns
pose – An instance of Pose which represents the joint configuration of joint_values as a pose in cartesian space
- Return type
- Raises
ServiceException – If query services from motion server are not available or finish unsuccessfully
TypeError – If joint_values is not of expected type JointValues
-
static
from_end_effector_name
(end_effector_name)[source] Creates an instance of MoveGroup and select the correct instance of EndEffector
- Parameters
end_effector_name (str convertable) – Name of the end_effector for which a instance of EndEffector should be created
- Returns
Instance of EndEffector for end effector with the name specified by end_effector name (instance is also hold by the created move_group)
- Return type
- Raises
TypeError – If end_effector_name ist not convertable to str
RuntimeError – If it is not possible to create an instance of EndEffector because the end effector specified by end_effector_name is not available
-
get_current_pose
()[source] Returns the current pose of the end effector
- Returns
pose – An instance of Pose which represents the current end effector pose
- Return type
- Raises
ServiceException – If query services from motion server are not available or finish unsuccessfully
-
inverse_kinematics
(pose, collision_check, seed=None, timeout=None, const_seed=False, attempts=1)[source]¶ inverse kinematic solutions for one pose
- Parameters
poses (Union[Pose, CartesianPath]) – Poses to transform to joint space
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration
timeout (Union[None, datatime.timedelta] (optional)) – timeout
const_seed (bool (optional default False)) – Determines if for each pose in poses the same seed should be used
attempts (int (optional default 1)) – number of attempts to find solution
- Returns
Instance of JointValues with a found solution
- Return type
- Raises
TypeError – If poses is not of correct type
ServiceException – If query service is not available
-
inverse_kinematics_many
(poses, collision_check, seed=None, timeout=None, const_seed=False, attempts=1)[source]¶ inverse kinematic solutions for many poses
- Parameters
poses (Union[Pose, CartesianPath]) – Poses to transform to joint space
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration
timeout (Union[None, datatime.timedelta] (optional)) – timeout
const_seed (bool (optional default False)) – Determines if for each pose in poses the same seed should be used
attempts (int (optional default 1)) – number of attempts to find solution
- Returns
Instance of IkResult with all found solutions as a JointPath and error codes
- Return type
IkResult
- Raises
TypeError – If poses is not of correct type
ServiceException – If query service is not available
-
link_name
¶ str end effector link name
- Type
link_name
-
motion_service
¶ MotionService Instance of MotionService which the move group and all end effectors use to communicate with the motion server
- Type
motion_service
-
move_group
¶ xamla_motion.MoveGroup Instance of MoveGroup which manages the move group where the end effector belongs to
- Type
move_group
-
move_poses
(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Asynchronous plan and execute trajectory from task space input
- Parameters
target (Union[Pose, CartesianPath]) – Target Pose or target CartesianPath
seed (Union[None, JointValues] (default None)) – Numerical seed to control joint configuration
velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task velocities If None the MoveGroup default is used
collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used
max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used
acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task accelerations If None the MoveGroup default is used
- Raises
TypeError – If target is not one of types Pose or CartesianPath If seed is defined and not of type JointValues If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_poses_collision_free
(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Asynchronous plan and execute collision free trajectory from task space input
- Parameters
target (Union[Pose, CartesianPath]) – Target joint positions
seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration
velocity_scaling (Union[None, float] (optional)) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool] (optional)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float] (optional)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float] (optional)) – Scaling factor which is applied on the maximal possible joint accelerations
- Raises
TypeError – If target is not one of types Union[Pose, CartesianPath] If seed is defined and not of type JointValues If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_poses_collision_free_supervised
(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plan collision free trajectory from task space input and create executor
- Parameters
target (Union[Pose, CartesianPath]) – Target joint positions
seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration
velocity_scaling (Union[None, float] (optional)) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool] (optional)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float] (optional)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float] (optional)) – Scaling factor which is applied on the maximal possible joint accelerations
- Returns
executor – Executor for supervised execution of collision free trajectory
- Return type
SteppedMotionClient
- Raises
TypeError – If target is not one of types Union[Pose, CartesianPath] If seed is defined and not of type JointValues If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_poses_linear
(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plans and executes a trajectory with linear movements from task space input
- Parameters
target (Union[Pose, CartesianPath]) – Target joint positions
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
- Raises
TypeError – If target is not one of types Union[Pose, CartesianPath] If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
move_poses_supervised
(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]¶ Plan trajectory from task space input and create executor
- Parameters
target (Union[Pose, CartesianPath]) – Target Pose or target CartesianPath
seed (Union[None, JointValues] (default None)) – Numerical seed to control joint configuration
velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task velocities If None the MoveGroup default is used
collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used
max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used
acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task accelerations If None the MoveGroup default is used
- Returns
executor – Executor for supervised execution of trajectory
- Return type
SteppedMotionClient
- Raises
TypeError – If target is not one of types Pose or CartesianPath If seed is defined and not of type JointValues If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-
name
¶ str (read only) end effector name
- Type
name
-
plan_poses_linear
(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None, seed=None)[source]¶ Plans a trajectory with linear movements from task space input
- Parameters
target (Union[Pose, CartesianPath]) – Target joint positions
velocity_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint velocities
collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed
max_deviation (Union[None, float]) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space
acceleration_scaling (Union[None, float]) – Scaling factor which is applied on the maximal possible joint accelerations
seed (Union[None, JointValues]) – Numerical seed to control joint configuration
- Returns
A tuple containing the trajectory and the plan parameters
- Return type
Tuple[JointTrajectory, PlanParameters]
- Raises
TypeError – If target is not one of types Union[Pose, CartesianPath] If all other inputs are not convertable to specified types
ValueError – If scaling inputs are not between 0.0 and 1.0
ServiceException – If underlying services from motion server are not available or finish not successfully
-