From a2a44646ababce82f513d4d6b929549f60d834ab Mon Sep 17 00:00:00 2001 From: Andrew Messing Date: Fri, 16 Jun 2023 18:44:58 +0000 Subject: [PATCH] Stopped ignoring FrameTreeSnapshot proto --- msg/Dock.msg | 76 +++++++++++-------------- msg/ImageCapture.msg | 3 +- msg/KinematicState.msg | 3 +- msg/LocalGrid.msg | 3 +- msg/ManipulationApiFeedbackResponse.msg | 3 +- msg/PickObjectInImage.msg | 3 +- msg/PointCloudSource.msg | 3 +- msg/RaycastResponse.msg | 3 +- msg/WalkToObjectInImage.msg | 3 +- msg/WorldObject.msg | 3 +- 10 files changed, 52 insertions(+), 51 deletions(-) diff --git a/msg/Dock.msg b/msg/Dock.msg index db70a99a..0480a92f 100644 --- a/msg/Dock.msg +++ b/msg/Dock.msg @@ -1,44 +1,36 @@ # AUTOMATICALLY GENERATED BY PROTO CONVERSION -# Name of the service to use. -string service_name -# Host machine of the directory server that the docking service is registered with. -string host - -# ID of docking station to dock at. -uint32 docking_station_id - -# Optional child node. Children will have access to the status variables gathered by this node. -# If specified, child node will determine success/failure of this node. -# -# DEPRECATED! Use docking_command_response_blackboard_key and -# docking_command_feedback_response_blackboard_key instead. - -# Name of the command status variable in the blackboard. This is the status of the docking -# command request made to the robot. Please refer to -# bosdyn.api.docking.DockingCommandResponse.Status for more details. Children can use this -# name to look up docking command status in the blackboard. If no name is provided, status will -# not be available. -# -# DEPRECATED! Use docking_command_response_blackboard_key and -# docking_command_feedback_response_blackboard_key instead. - -# Name of the feedback status variable in the blackboard. This is the feedback provided while -# docking is in progress. Please refer to -# bosdyn.api.docking.DockingCommandFeedbackResponse.Status for a list of possible status -# values. Children can use this name to look up docking status in the blackboard. If no name -# is provided, status will not be available. -# -# DEPRECATED! Use docking_command_response_blackboard_key and -# docking_command_feedback_response_blackboard_key instead. - -# Defines how we use the "pre-docking" behavior. -bosdyn_msgs/PrepPoseBehavior prep_pose_behavior - -# If provided, this will write the last DockingCommandFeedbackResponse message -# to a blackboard variable with this name. -string docking_command_feedback_response_blackboard_key - -# If provided, this will write the last DockingCommandResponse message to -# a blackboard variable with this name. -string docking_command_response_blackboard_key +# The dock itself and the target associated with it + +# The docking station ID of the dock corresponds to the number printed on the +# fiducial, below the part of the fiducial that looks like a QR code. +# Only fiducial IDs greater than or equal to 500 should be +# used here because they are reserved for docks. +uint32 dock_id + +# To maximize reliability, at record time, the client should dock the robot +# while graph_nav is still recording. When the robot is finished docking, +# the client should create a waypoint on top of the dock, while the robot is +# docked, and then stop recording. The waypoint created while the +# robot is sitting on the dock should be specified here. +string docked_waypoint_id + +# When it is time for the robot to dock, it will approach this target +# before issuing docking commands. If the user is using graph_nav, the +# final waypoint in the NavigateRoute OR the waypoint ID in the +# NavigateTo MUST be at the docking prep pose. To do this, send a docking +# command to move the robot to the docking prep pose. Then, create a +# waypoint at the docking prep pose location. Graph_nav is responsible for +# navigating the robot to the docking prep pose. Once the robot is in the +# docking prep pose, the docking service does the rest. +bosdyn_msgs/Target target_prep_pose +bool target_prep_pose_is_set + +# At mission playback, if the robot is unable to reach the dock OR successfully +# dock, the mission will let the operator know with a user question. If the operator +# does not answer, the robot will safely power off. This parameter controls +# how long the operator has to answer. +# This parameter also controls how long robot will wait to retry to undock on +# a failed undock. +builtin_interfaces/Duration prompt_duration +bool prompt_duration_is_set diff --git a/msg/ImageCapture.msg b/msg/ImageCapture.msg index 7084e8b2..4237618a 100644 --- a/msg/ImageCapture.msg +++ b/msg/ImageCapture.msg @@ -9,7 +9,8 @@ bool acquisition_time_is_set # A tree-based collection of transformations, which will include the transformations to each image's # sensor in addition to transformations to the common frames ("vision", "body", "odom"). # All transforms within the snapshot are at the acquistion time of the image. -# FrameTreeSnapshot transforms_snapshot = 31; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set # The frame name for the image's sensor source. This will be included in the transform snapshot. string frame_name_image_sensor diff --git a/msg/KinematicState.msg b/msg/KinematicState.msg index c6575c20..290bb875 100644 --- a/msg/KinematicState.msg +++ b/msg/KinematicState.msg @@ -14,7 +14,8 @@ bool acquisition_timestamp_is_set # robot body ("body") in addition to transformations to the common frames ("world", "dr") and # ground plane estimate "gpe". # All transforms within the snapshot are at the acquisition time of kinematic state. -# FrameTreeSnapshot transforms_snapshot = 31; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set # Velocity of the body frame with respect to vision frame and expressed in vision frame. # The linear velocity is applied at the origin of the body frame. diff --git a/msg/LocalGrid.msg b/msg/LocalGrid.msg index dc020a6b..92129c24 100644 --- a/msg/LocalGrid.msg +++ b/msg/LocalGrid.msg @@ -13,7 +13,8 @@ bool acquisition_time_is_set # A tree-based collection of transformations, which will include the transformations to each of # the returned local grids in addition to transformations to the common frames ("vision", "body", "odom"). # All transforms within the snapshot are at the acquistion time of the local grid. -# FrameTreeSnapshot transforms_snapshot = 31; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set # The frame name for the local grid data. This frame refers to the corner of cell (0, 0), such that # the map data is in the +x, +y quadrant. diff --git a/msg/ManipulationApiFeedbackResponse.msg b/msg/ManipulationApiFeedbackResponse.msg index e60aa203..17c8c836 100644 --- a/msg/ManipulationApiFeedbackResponse.msg +++ b/msg/ManipulationApiFeedbackResponse.msg @@ -20,4 +20,5 @@ bosdyn_msgs/ManipulationFeedbackState current_state # "gripper_nearest_object": # If the range camera in the hand senses an object, this frame will have the position of # the nearest object. This is useful for getting a ballpark range measurement. -# FrameTreeSnapshot transforms_snapshot_manipulation_data = 3; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot_manipulation_data +bool transforms_snapshot_manipulation_data_is_set diff --git a/msg/PickObjectInImage.msg b/msg/PickObjectInImage.msg index 0374842e..4e914d44 100644 --- a/msg/PickObjectInImage.msg +++ b/msg/PickObjectInImage.msg @@ -7,7 +7,8 @@ bool pixel_xy_is_set # A tree-based collection of transformations, which will include the transformations to each image's # sensor in addition to transformations to the common frames ("vision", "body", "odom"). # All transforms within the snapshot are at the acquistion time of the image. -# FrameTreeSnapshot transforms_snapshot_for_camera = 2; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot_for_camera +bool transforms_snapshot_for_camera_is_set # The frame name for the image's sensor source. This must be included in the transform snapshot. string frame_name_image_sensor diff --git a/msg/PointCloudSource.msg b/msg/PointCloudSource.msg index ecbf1080..79898553 100644 --- a/msg/PointCloudSource.msg +++ b/msg/PointCloudSource.msg @@ -16,5 +16,6 @@ bool acquisition_time_is_set # A tree-based collection of transformations, which will include the transformations # to the point cloud data frame and the point cloud sensor frame. -# FrameTreeSnapshot transforms_snapshot = 31; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set diff --git a/msg/RaycastResponse.msg b/msg/RaycastResponse.msg index 12673c18..84fe4f2f 100644 --- a/msg/RaycastResponse.msg +++ b/msg/RaycastResponse.msg @@ -24,4 +24,5 @@ bosdyn_msgs/RayIntersection[] hits # # Note that each object's frame names are defined within the properties # submessage e.g. "frame_name". -# FrameTreeSnapshot transforms_snapshot = 4; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set diff --git a/msg/WalkToObjectInImage.msg b/msg/WalkToObjectInImage.msg index 8de5c9f2..c8143f4e 100644 --- a/msg/WalkToObjectInImage.msg +++ b/msg/WalkToObjectInImage.msg @@ -7,7 +7,8 @@ bool pixel_xy_is_set # A tree-based collection of transformations, which will include the transformations to each image's # sensor in addition to transformations to the common frames ("vision", "body", "odom"). # All transforms within the snapshot are at the acquistion time of the image. -# FrameTreeSnapshot transforms_snapshot_for_camera = 2; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot_for_camera +bool transforms_snapshot_for_camera_is_set # The frame name for the image's sensor source. This will be included in the transform snapshot. string frame_name_image_sensor diff --git a/msg/WorldObject.msg b/msg/WorldObject.msg index a8a34f06..67b008a3 100644 --- a/msg/WorldObject.msg +++ b/msg/WorldObject.msg @@ -23,7 +23,8 @@ bool acquisition_time_is_set # "body", "odom"). All transforms within the snapshot are at the acquisition time of the world object. # Note that each object's frame names are defined within the properties submessage. For example, # the apriltag frame name is defined in the AprilTagProperties message as "frame_name_fiducial" -# FrameTreeSnapshot transforms_snapshot = 31; +bosdyn_msgs/FrameTreeSnapshot transforms_snapshot +bool transforms_snapshot_is_set # The drawable properties describe geometric shapes associated with an object. bosdyn_msgs/DrawableProperties[] drawable_properties