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

[SW-822] Spot Driver without gripper #430

Merged
merged 5 commits into from
Jul 16, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
3 changes: 3 additions & 0 deletions spot_driver/config/spot_ros_example.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -42,3 +42,6 @@
virtual_camera_plane_distance: 0.5
# The stitched image will be of size (<frontleft image width>, <frontleft image height> + row_padding)
stitched_image_row_padding: 1182

# Change to True if missing gripper on arm
gripperless: False
42 changes: 24 additions & 18 deletions spot_driver/spot_driver/spot_ros2.py
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,8 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
self.declare_parameter("spot_name", "")
self.declare_parameter("mock_enable", False)

self.declare_parameter("gripperless", False)

# When we send very long trajectories to Spot, we create batches of
# given size. If we do not batch a long trajectory, Spot will reject it.
self.declare_parameter(self.TRAJECTORY_BATCH_SIZE_PARAM, 100)
Expand Down Expand Up @@ -287,6 +289,8 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
self.graph_nav_seed_frame: str = self.get_parameter("graph_nav_seed_frame").value
self.initialize_spot_cam: bool = self.get_parameter("initialize_spot_cam").value

self.gripperless: bool = self.get_parameter("gripperless").value

self._wait_for_goal: Optional[WaitForGoal] = None
self.goal_handle: Optional[ServerGoalHandle] = None

Expand Down Expand Up @@ -412,6 +416,7 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
port=self.port,
logger=self.cam_logger,
cert_resource_glob=self.certificate,
gripperless=self.gripperless,
)
except SystemError:
self.spot_cam_wrapper = None
Expand All @@ -428,7 +433,7 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
has_arm = self.mock_has_arm
if self.spot_wrapper is not None:
has_arm = self.spot_wrapper.has_arm()
if has_arm:
if has_arm and not self.gripperless:
all_cameras.append("hand")
self.declare_parameter("cameras_used", all_cameras)
Comment on lines +436 to 438
Copy link
Collaborator

@khughes-bdai khughes-bdai Jul 15, 2024

Choose a reason for hiding this comment

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

I think this param is not used at all in this node and can be completely deleted (it's all in C++ now)

self.cameras_used = self.get_parameter("cameras_used")
Expand Down Expand Up @@ -564,22 +569,23 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
callback_group=self.group,
)

self.create_service(
Trigger,
"open_gripper",
lambda request, response: self.service_wrapper(
"open_gripper", self.handle_open_gripper, request, response
),
callback_group=self.group,
)
self.create_service(
Trigger,
"close_gripper",
lambda request, response: self.service_wrapper(
"close_gripper", self.handle_close_gripper, request, response
),
callback_group=self.group,
)
if not self.gripperless:
self.create_service(
Trigger,
"open_gripper",
lambda request, response: self.service_wrapper(
"open_gripper", self.handle_open_gripper, request, response
),
callback_group=self.group,
)
self.create_service(
Trigger,
"close_gripper",
lambda request, response: self.service_wrapper(
"close_gripper", self.handle_close_gripper, request, response
),
callback_group=self.group,
)

self.create_service(
SetBool,
Expand Down Expand Up @@ -861,7 +867,7 @@ def __init__(self, parameter_list: Optional[typing.List[Parameter]] = None, **kw
self.handle_graph_nav_set_localization,
callback_group=self.group,
)
if has_arm:
if has_arm and self.gripperless:
Copy link
Collaborator

Choose a reason for hiding this comment

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

@tcappellari-bdai shouldn't this be if has_arm and not self.gripperless?

self.create_service(
GetGripperCameraParameters,
"get_gripper_camera_parameters",
Expand Down
Loading