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

[MAPLE-743] Add non blocking to hand_pose and change default traj timing #146

Merged
merged 3 commits into from
Oct 17, 2024
Merged
Changes from 2 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
15 changes: 10 additions & 5 deletions spot_wrapper/spot_arm.py
Original file line number Diff line number Diff line change
Expand Up @@ -447,9 +447,10 @@ def hand_pose(
qy: float,
qz: float,
qw: float,
duration: float = 0.125,
duration: float = 0.0,
scastro-bdai marked this conversation as resolved.
Show resolved Hide resolved
ref_frame: str = "body",
ensure_power_on_and_stand: bool = True,
blocking: bool = True,
) -> typing.Tuple[bool, str]:
"""
Set the pose of the hand
Expand Down Expand Up @@ -483,11 +484,14 @@ def hand_pose(
# Rotation as a quaternion.
rotation = geometry_pb2.Quaternion(w=qw, x=qx, y=qy, z=qz)

traj_duration = seconds_to_duration(duration)

# Build the SE(3) pose of the desired hand position in the moving body frame.
hand_pose = geometry_pb2.SE3Pose(position=position, rotation=rotation)
hand_pose_traj_point = trajectory_pb2.SE3TrajectoryPoint(pose=hand_pose, time_since_reference=traj_duration)
hand_pose_traj_point = trajectory_pb2.SE3TrajectoryPoint(pose=hand_pose)
if duration != 0.0:
scastro-bdai marked this conversation as resolved.
Show resolved Hide resolved
traj_duration = seconds_to_duration(duration)
hand_pose_traj_point = trajectory_pb2.SE3TrajectoryPoint(
pose=hand_pose, time_since_reference=traj_duration
)
hand_trajectory = trajectory_pb2.SE3Trajectory(points=[hand_pose_traj_point])

arm_cartesian_command = arm_command_pb2.ArmCartesianCommand.Request(
Expand All @@ -504,7 +508,8 @@ def hand_pose(

# Send the request
cmd_id = self._robot_command_client.robot_command(robot_command)
self.wait_for_arm_command_to_complete(cmd_id)
if blocking:
self.wait_for_arm_command_to_complete(cmd_id)

except Exception as e:
return (
Expand Down