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

Fb set arm velocity #366

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open

Conversation

MGBla
Copy link
Contributor

@MGBla MGBla commented Apr 26, 2024

Change Overview

Corresponding Driver calls to the PR on the wrapper Repo 104 to control the robot using a VelocityCommand interface. I decided to use a topic interface to control the arm since i want to have direct control over it instead of a longer running service call.
The angular and Cartesian velocity were thoroughly tested during operation on our spot. For the cylindrical velocity I performed some basic tests but didn't evaluate over hours as the other two input methods since I don't really use them in this reference frame.

Testing Done

- [x] tested that these new services work on robot

Copy link
Collaborator

@tcappellari-bdai tcappellari-bdai left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This would be better as a service call instead of a subscriber callback.
There are also some conversion methods we have already provided to convert between protobufs and ROS messages so you don't have to convert them manually.

spot_driver/spot_driver/spot_ros2.py Outdated Show resolved Hide resolved
spot_driver/spot_driver/spot_ros2.py Outdated Show resolved Hide resolved
Comment on lines +2936 to +2965
cylindrical_velocity = arm_command_pb2.ArmVelocityCommand.CylindricalVelocity()
cylindrical_velocity.linear_velocity.r = arm_velocity_command.command.cylindrical_velocity.linear_velocity.r
cylindrical_velocity.linear_velocity.theta = (
arm_velocity_command.command.cylindrical_velocity.linear_velocity.theta
)
cylindrical_velocity.linear_velocity.z = arm_velocity_command.command.cylindrical_velocity.linear_velocity.z

angular_velocity = geometry_pb2.Vec3(
x=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.x,
y=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.y,
z=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.z,
)

cartesian_velocity = arm_command_pb2.ArmVelocityCommand.CartesianVelocity()
cartesian_velocity.velocity_in_frame_name.x = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.x
)
cartesian_velocity.velocity_in_frame_name.y = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.y
)
cartesian_velocity.velocity_in_frame_name.z = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.z
)
cartesian_velocity.frame_name = arm_velocity_command.command.cartesian_velocity.frame_name

proto_command = arm_command_pb2.ArmVelocityCommand.Request(
cylindrical_velocity=cylindrical_velocity,
angular_velocity_of_hand_rt_odom_in_hand=angular_velocity,
cartesian_velocity=cartesian_velocity,
)
Copy link
Collaborator

@khughes-bdai khughes-bdai May 21, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should be able to replace this with the following, using some built in proto to ros conversion:

Suggested change
cylindrical_velocity = arm_command_pb2.ArmVelocityCommand.CylindricalVelocity()
cylindrical_velocity.linear_velocity.r = arm_velocity_command.command.cylindrical_velocity.linear_velocity.r
cylindrical_velocity.linear_velocity.theta = (
arm_velocity_command.command.cylindrical_velocity.linear_velocity.theta
)
cylindrical_velocity.linear_velocity.z = arm_velocity_command.command.cylindrical_velocity.linear_velocity.z
angular_velocity = geometry_pb2.Vec3(
x=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.x,
y=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.y,
z=arm_velocity_command.angular_velocity_of_hand_rt_odom_in_hand.z,
)
cartesian_velocity = arm_command_pb2.ArmVelocityCommand.CartesianVelocity()
cartesian_velocity.velocity_in_frame_name.x = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.x
)
cartesian_velocity.velocity_in_frame_name.y = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.y
)
cartesian_velocity.velocity_in_frame_name.z = (
arm_velocity_command.command.cartesian_velocity.velocity_in_frame_name.z
)
cartesian_velocity.frame_name = arm_velocity_command.command.cartesian_velocity.frame_name
proto_command = arm_command_pb2.ArmVelocityCommand.Request(
cylindrical_velocity=cylindrical_velocity,
angular_velocity_of_hand_rt_odom_in_hand=angular_velocity,
cartesian_velocity=cartesian_velocity,
)
proto_command = arm_command_pb2.ArmVelocityCommand.Request()
convert(arm_velocity_command, proto_command)

Can you verify that this still works with your example?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Will test it later this afternoon on the robot :)

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hello, just wondering if you had a chance to test this out?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hey, sorry didn't had the time yet and our robot is not available for the next two weeks. I will test it then

cartesian_velocity=cartesian_velocity,
)

return self.spot_wrapper.spot_arm.handle_arm_velocity(proto_command)
Copy link
Collaborator

@khughes-bdai khughes-bdai Jun 3, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
return self.spot_wrapper.spot_arm.handle_arm_velocity(proto_command)
return self.spot_wrapper.spot_arm.handle_arm_velocity(proto_command, self.cmd_duration)

If we want this to mimic the cmd_vel topic, we can use the same duration field as it. This also makes it possible to change the rate from the ROS side of things.

khughes-bdai pushed a commit to bdaiinstitute/spot_wrapper that referenced this pull request Jun 5, 2024
…mand (#104)

## Change Overview

Added the ability to set a Velocity command for the arm. This enables a user to have direct translational and rotational  control of the TCP movement using a controller or any other input device. The corresponding [PR](bdaiinstitute/spot_ros2#366) on the driver Repo provides a topic interface to send the corresponding movement command. 
The angular and Cartesian velocity were thoroughly tested during operation on our spot. For the cylindrical velocity I performed some basic tests but didn't evaluate over hours as the other two input methods since I don't really use them in this reference frame.

## Testing Done
    - [x] tested that these new functionality work on robot
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants