drims2_motion_server.motion_client module

class drims2_motion_server.motion_client.MotionClient(move_to_pose_action_name: str = 'move_to_pose', move_to_joint_action_name: str = 'move_to_joint', gripper_action_name: str = 'robotiq_action_controller/gripper_cmd')

Bases: Node

ROS 2 Client for controlling robot motion and gripper.

This class provides a simplified interface for sending commands to the robot via action servers and services. Supported operations: - Move to a target pose - Move to joint configurations - Attach/detach objects - Move the gripper

attach_object(object_id: str, target_frame_id: str) bool

Attach an object to the robot (e.g., to the gripper).

Args:

object_id (str): ID of the object in the MoveIt scene. target_frame_id (str): Frame of the robot to which the object should be attached.

Returns:

bool: True if the operation succeeded, False otherwise.

Raises:

RuntimeError: If the service is not available.

detach_object(object_id: str) bool

Detach an object from the robot.

Args:

object_id (str): ID of the object to detach.

Returns:

bool: True if the operation succeeded, False otherwise.

Raises:

RuntimeError: If the service is not available.

gripper_command(position: float, max_effort: float = 0.0) Tuple[bool, bool]

Send a command to the gripper, i.e, move it to a specific position.

Args:

position (float): Target position of the gripper (units depend on controller configuration). max_effort (float, optional): Maximum force applied. Defaults to 0.0 (it’s enough most of the time).

Returns:
Tuple[bool, bool]:
  • reached_goal (bool): True if the gripper reached the target position.

  • stalled (bool): True if the gripper stalled during execution.

Raises:

RuntimeError: If the action server is not available or the goal was rejected.

move_to_joint(joint_positions: list[float]) MoveItErrorCodes

Move the robot to a specific joint configuration.

Args:

joint_positions (list[float]): List of target joint values.

Returns:

MoveItErrorCodes: Result code returned by the motion planner.

Raises:

RuntimeError: If the action server is not available or the goal was rejected.

move_to_pose(pose: PoseStamped, cartesian_motion: bool = False) MoveItErrorCodes

Move the robot to a target pose.

Args:

pose (PoseStamped): Target pose for the robot. cartesian_motion (bool, optional): If True, uses Cartesian trajectories. Defaults to False.

Returns:

MoveItErrorCodes: Result code returned by the motion planner.

Raises:

RuntimeError: If the action server is not available or the goal was rejected.