diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile index 2ce4e9118..e2029d0f7 100644 --- a/.devcontainer/Dockerfile +++ b/.devcontainer/Dockerfile @@ -30,23 +30,24 @@ RUN DEBIAN_FRONTEND=noninteractive apt-get update -q && \ RUN source "/opt/ros/${ROS_DISTRO}/setup.bash" # Install bosdyn_msgs package -RUN curl -sL https://github.com/bdaiinstitute/bosdyn_msgs/releases/download/v3.3.2-AMD64/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb --output /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb --silent \ - && dpkg -i /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb \ - && rm /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb +RUN curl -sL https://github.com/bdaiinstitute/bosdyn_msgs/releases/download/4.0.0-2/ros-humble-bosdyn_msgs_4.0.0-2-jammy_amd64.run --output /tmp/ros-humble-bosdyn_msgs_4.0.0-2-jammy_amd64.run --silent \ + && chmod +x /tmp/ros-humble-bosdyn_msgs_4.0.0-2-jammy_amd64.run \ + && ((yes || true) | /tmp/ros-humble-bosdyn_msgs_4.0.0-2-jammy_amd64.run) \ + && rm /tmp/ros-humble-bosdyn_msgs_4.0.0-2-jammy_amd64.run # Install spot_cpp_sdk package -RUN curl -sL https://github.com/bdaiinstitute/spot-cpp-sdk/releases/download/3.3.2/spot-cpp-sdk_3.3.2_amd64.deb --output /tmp/spot-cpp-sdk_3.3.2_amd64.deb --silent \ - && dpkg -i /tmp/spot-cpp-sdk_3.3.2_amd64.deb \ - && rm /tmp/spot-cpp-sdk_3.3.2_amd64.deb +RUN curl -sL https://github.com/bdaiinstitute/spot-cpp-sdk/releases/download/4.0.0/spot-cpp-sdk_4.0.0_amd64.deb --output /tmp/spot-cpp-sdk_4.0.0_amd64.deb --silent \ + && dpkg -i /tmp/spot-cpp-sdk_4.0.0_amd64.deb \ + && rm /tmp/spot-cpp-sdk_4.0.0_amd64.deb # Install bosdyn_msgs missing dependencies RUN python -m pip install --no-cache-dir --upgrade pip==22.3.1 \ && pip install --root-user-action=ignore --no-cache-dir --default-timeout=900 \ numpy==1.24.1 \ - bosdyn-client==3.3.2 \ - bosdyn-mission==3.3.2 \ - bosdyn-api==3.3.2 \ - bosdyn-core==3.3.2 \ + bosdyn-client==4.0.0 \ + bosdyn-mission==4.0.0 \ + bosdyn-api==4.0.0 \ + bosdyn-core==4.0.0 \ pip cache purge # Install spot_wrapper requirements diff --git a/README.md b/README.md index 539b2fda2..8a3a66fd0 100644 --- a/README.md +++ b/README.md @@ -19,7 +19,7 @@ # Overview This is a ROS2 package for Boston Dynamics' Spot. The package contains all necessary topics, services and actions to teleoperate or navigate Spot. -This package is derived from this [ROS1 package](https://github.com/heuristicus/spot_ros). This package currently corresponds to version 3.3.2 of the [spot-sdk](https://github.com/boston-dynamics/spot-sdk/releases/tag/v3.3.2). +This package is derived from this [ROS1 package](https://github.com/heuristicus/spot_ros). This package currently corresponds to version 4.0.0 of the [spot-sdk](https://github.com/boston-dynamics/spot-sdk/releases/tag/v4.0.0). ## Prerequisites This package is tested for Ubuntu 22.04 and ROS 2 Humble, which can be installed following [this guide](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). diff --git a/examples/inverse_kinematics_example/README.md b/examples/inverse_kinematics_example/README.md index 6d250a00c..f6a1ba0b4 100644 --- a/examples/inverse_kinematics_example/README.md +++ b/examples/inverse_kinematics_example/README.md @@ -121,10 +121,10 @@ In ROS2, we convert the created protobuf ROS2 request and call a ROS2 service. ), ) request = GetInverseKinematicSolutions.Request() - conv.convert_proto_to_bosdyn_msgs_inverse_kinematics_request(ik_request, request.request) + convert(ik_request, request.request) ik_reponse = self._ik_client.call(request) proto = inverse_kinematics_pb2.InverseKinematicsResponse() - conv.convert_bosdyn_msgs_inverse_kinematics_response_to_proto(ik_reponse.response, proto) + convert(ik_reponse.response, proto) return proto ``` diff --git a/examples/inverse_kinematics_example/inverse_kinematics_example/send_inverse_kinematics_requests.py b/examples/inverse_kinematics_example/inverse_kinematics_example/send_inverse_kinematics_requests.py index ddf38cb3c..f167f541d 100644 --- a/examples/inverse_kinematics_example/inverse_kinematics_example/send_inverse_kinematics_requests.py +++ b/examples/inverse_kinematics_example/inverse_kinematics_example/send_inverse_kinematics_requests.py @@ -35,12 +35,12 @@ ) from bosdyn.client.math_helpers import Quat, SE3Pose from bosdyn.client.robot_command import RobotCommandBuilder +from bosdyn_msgs.conversions import convert from rclpy.node import Node from tf2_ros import TransformBroadcaster from utilities.simple_spot_commander import SimpleSpotCommander from utilities.tf_listener_wrapper import TFListenerWrapper -import spot_driver.conversions as conv from spot_msgs.action import RobotCommand # type: ignore from spot_msgs.srv import GetInverseKinematicSolutions # type: ignore @@ -102,7 +102,7 @@ def _ready_arm(self) -> bool: """ command = RobotCommandBuilder.arm_ready_command() action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(command, action_goal.command) + convert(command, action_goal.command) return self._robot_command_client.send_goal_and_wait("ready_arm", action_goal) def _arm_stow(self) -> bool: @@ -111,7 +111,7 @@ def _arm_stow(self) -> bool: """ command = RobotCommandBuilder.arm_stow_command() action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(command, action_goal.command) + convert(command, action_goal.command) return self._robot_command_client.send_goal_and_wait("arm_stow", action_goal) def _send_ik_request( @@ -133,11 +133,11 @@ def _send_ik_request( ), ) request = GetInverseKinematicSolutions.Request() - conv.convert_proto_to_bosdyn_msgs_inverse_kinematics_request(ik_request, request.request) + convert(ik_request, request.request) ik_reponse = self._ik_client.call(request) proto = inverse_kinematics_pb2.InverseKinematicsResponse() - conv.convert_bosdyn_msgs_inverse_kinematics_response_to_proto(ik_reponse.response, proto) + convert(ik_reponse.response, proto) return proto def test_run(self) -> bool: @@ -275,7 +275,7 @@ def test_run(self) -> bool: wr1_T_tool.to_proto() ) arm_command_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(arm_command, arm_command_goal.command) + convert(arm_command, arm_command_goal.command) result = self._robot_command_client.send_goal_and_wait( action_name="arm_move_one", goal=arm_command_goal, timeout_sec=5 ) diff --git a/examples/simple_arm_motion/README.md b/examples/simple_arm_motion/README.md index ab771b4c3..9d7a54da2 100644 --- a/examples/simple_arm_motion/README.md +++ b/examples/simple_arm_motion/README.md @@ -134,7 +134,7 @@ In ROS2, we convert the created protobuf to a ROS2 action goal and we use the ac ```python # Convert to a ROS message action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(command, action_goal.command) + convert(command, action_goal.command) # Send the request and wait until the arm arrives at the goal node.get_logger().info('Moving arm to position 1.') robot_command_client.send_goal_and_wait(action_goal) diff --git a/examples/simple_arm_motion/simple_arm_motion/arm_simple.py b/examples/simple_arm_motion/simple_arm_motion/arm_simple.py index ceef2d784..a24515143 100644 --- a/examples/simple_arm_motion/simple_arm_motion/arm_simple.py +++ b/examples/simple_arm_motion/simple_arm_motion/arm_simple.py @@ -9,10 +9,10 @@ from bosdyn.client import math_helpers from bosdyn.client.frame_helpers import GRAV_ALIGNED_BODY_FRAME_NAME, ODOM_FRAME_NAME from bosdyn.client.robot_command import RobotCommandBuilder +from bosdyn_msgs.conversions import convert from utilities.simple_spot_commander import SimpleSpotCommander from utilities.tf_listener_wrapper import TFListenerWrapper -import spot_driver.conversions as conv from spot_msgs.action import RobotCommand # type: ignore @@ -97,7 +97,7 @@ def hello_arm(robot_name: Optional[str] = None) -> bool: # Convert to a ROS message action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(command, action_goal.command) + convert(command, action_goal.command) # Send the request and wait until the arm arrives at the goal logger.info("Moving arm to position 1.") robot_command_client.send_goal_and_wait("arm_move_one", action_goal) @@ -133,7 +133,7 @@ def hello_arm(robot_name: Optional[str] = None) -> bool: # Convert to a ROS message action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(command, action_goal.command) + convert(command, action_goal.command) # Send the request and wait until the arm arrives at the goal logger.info("Moving arm to position 2.") robot_command_client.send_goal_and_wait("arm_move_two", action_goal) diff --git a/examples/simple_walk_forward/README.md b/examples/simple_walk_forward/README.md index 62fdd71d4..bfa8c1444 100644 --- a/examples/simple_walk_forward/README.md +++ b/examples/simple_walk_forward/README.md @@ -103,7 +103,7 @@ Now we construct a goal to send to the Spot driver: goal_x=world_t_goal.x, goal_y=world_t_goal.y, goal_heading=world_t_goal.angle, frame_name=VISION_FRAME_NAME) action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(proto_goal, action_goal.command) + convert(proto_goal, action_goal.command) ``` This constructs a protobuf message using the BD built in tools and converts it into a ROS action goal of a type that can be sent by our action client. diff --git a/examples/simple_walk_forward/simple_walk_forward/walk_forward.py b/examples/simple_walk_forward/simple_walk_forward/walk_forward.py index ee1780e0f..45929f8ee 100644 --- a/examples/simple_walk_forward/simple_walk_forward/walk_forward.py +++ b/examples/simple_walk_forward/simple_walk_forward/walk_forward.py @@ -9,11 +9,11 @@ from bosdyn.client.frame_helpers import BODY_FRAME_NAME, VISION_FRAME_NAME from bosdyn.client.math_helpers import SE2Pose from bosdyn.client.robot_command import RobotCommandBuilder +from bosdyn_msgs.conversions import convert from rclpy.node import Node from utilities.simple_spot_commander import SimpleSpotCommander from utilities.tf_listener_wrapper import TFListenerWrapper -import spot_driver.conversions as conv from spot_msgs.action import RobotCommand # type: ignore # Where we want the robot to walk to relative to itself @@ -74,7 +74,7 @@ def walk_forward_with_world_frame_goal(self) -> None: frame_name=VISION_FRAME_NAME, # use Boston Dynamics' frame conventions ) action_goal = RobotCommand.Goal() - conv.convert_proto_to_bosdyn_msgs_robot_command(proto_goal, action_goal.command) + convert(proto_goal, action_goal.command) self._robot_command_client.send_goal_and_wait("walk_forward", action_goal) self._logger.info("Successfully walked forward") diff --git a/install_spot_ros2.sh b/install_spot_ros2.sh index baec2f2b7..703563e51 100755 --- a/install_spot_ros2.sh +++ b/install_spot_ros2.sh @@ -1,11 +1,13 @@ -ARM=false +ARCH="amd64" +SDK_VERSION="4.0.0" +MSG_VERSION="${SDK_VERSION}-2" ROS_DISTRO=humble HELP=$'--arm64: Installs ARM64 version' REQUIREMENTS_FILE=spot_wrapper/requirements.txt while true; do case "$1" in - --arm64 ) ARM=true; shift ;; + --arm64 ) ARCH="arm64"; shift ;; -h | --help ) echo "$HELP"; exit 0;; -- ) shift; break ;; * ) break ;; @@ -29,25 +31,13 @@ sudo apt-get install -y python3-distutils sudo apt-get install -y python3-apt sudo pip3 install --force-reinstall -v "setuptools==59.6.0" +# Install bosdyn_msgs - automatic conversions of BD protobufs to ROS messages +wget -q -O /tmp/ros-humble-bosdyn_msgs_${MSG_VERSION}-jammy_${ARCH}.run https://github.com/bdaiinstitute/bosdyn_msgs/releases/download/${MSG_VERSION}/ros-humble-bosdyn_msgs_${MSG_VERSION}-jammy_${ARCH}.run +chmod +x /tmp/ros-humble-bosdyn_msgs_${MSG_VERSION}-jammy_${ARCH}.run +sudo /tmp/ros-humble-bosdyn_msgs_${MSG_VERSION}-jammy_${ARCH}.run +rm /tmp/ros-humble-bosdyn_msgs_${MSG_VERSION}-jammy_${ARCH}.run -if $ARM; then - # Install bosdyn_msgs - automatic conversions of BD protobufs to ROS messages - wget -q -O /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_arm64.deb https://github.com/bdaiinstitute/bosdyn_msgs/releases/download/v3.3.2-ARM64/ros-humble-bosdyn-msgs_3.3.2-0jammy_arm64.deb - sudo dpkg -i /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_arm64.deb - rm /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_arm64.deb - - # Install spot-cpp-sdk - wget -q -O /tmp/spot-cpp-sdk_3.3.2_arm64.deb https://github.com/bdaiinstitute/spot-cpp-sdk/releases/download/3.3.2/spot-cpp-sdk_3.3.2_arm64.deb - sudo dpkg -i /tmp/spot-cpp-sdk_3.3.2_arm64.deb - rm /tmp/spot-cpp-sdk_3.3.2_arm64.deb -else - # Install bosdyn_msgs - automatic conversions of BD protobufs to ROS messages - wget -q -O /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb https://github.com/bdaiinstitute/bosdyn_msgs/releases/download/v3.3.2-AMD64/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb - sudo dpkg -i /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb - rm /tmp/ros-humble-bosdyn-msgs_3.3.2-0jammy_amd64.deb - - # Install spot-cpp-sdk - wget -q -O /tmp/spot-cpp-sdk_3.3.2_amd64.deb https://github.com/bdaiinstitute/spot-cpp-sdk/releases/download/3.3.2/spot-cpp-sdk_3.3.2_amd64.deb - sudo dpkg -i /tmp/spot-cpp-sdk_3.3.2_amd64.deb - rm /tmp/spot-cpp-sdk_3.3.2_amd64.deb -fi +# Install spot-cpp-sdk +wget -q -O /tmp/spot-cpp-sdk_${SDK_VERSION}_${ARCH}.deb https://github.com/bdaiinstitute/spot-cpp-sdk/releases/download/${SDK_VERSION}/spot-cpp-sdk_${SDK_VERSION}_${ARCH}.deb +sudo dpkg -i /tmp/spot-cpp-sdk_${SDK_VERSION}_${ARCH}.deb +rm /tmp/spot-cpp-sdk_${SDK_VERSION}_${ARCH}.deb diff --git a/spot_driver/CMakeLists.txt b/spot_driver/CMakeLists.txt index 7d0cde44a..a6f1b1c71 100644 --- a/spot_driver/CMakeLists.txt +++ b/spot_driver/CMakeLists.txt @@ -11,6 +11,8 @@ endif() set(CMAKE_EXPORT_COMPILE_COMMANDS ON) set(THIS_PACKAGE_INCLUDE_ROS_DEPENDS + bosdyn_api_msgs + bosdyn_spot_api_msgs cv_bridge geometry_msgs rclcpp diff --git a/spot_driver/include/spot_driver/conversions/common_conversions.hpp b/spot_driver/include/spot_driver/conversions/common_conversions.hpp index 93f2752d2..57fa18fb8 100644 --- a/spot_driver/include/spot_driver/conversions/common_conversions.hpp +++ b/spot_driver/include/spot_driver/conversions/common_conversions.hpp @@ -5,11 +5,10 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -28,7 +27,7 @@ namespace spot_ros2 { void convertToProto(const builtin_interfaces::msg::Time& ros_msg, google::protobuf::Timestamp& proto); -void convertToProto(const bosdyn_msgs::msg::RequestHeader& ros_msg, bosdyn::api::RequestHeader& proto); +void convertToProto(const bosdyn_api_msgs::msg::RequestHeader& ros_msg, bosdyn::api::RequestHeader& proto); void convertToProto(const geometry_msgs::msg::Vector3& ros_msg, bosdyn::api::Vec3& proto); @@ -40,16 +39,16 @@ void convertToProto(const geometry_msgs::msg::Pose& ros_msg, bosdyn::api::SE3Pos void convertToProto(const double& ros_msg, google::protobuf::DoubleValue& proto); -void convertToProto(const bosdyn_msgs::msg::ArmJointPosition& ros_msg, bosdyn::api::ArmJointPosition& proto); +void convertToProto(const bosdyn_api_msgs::msg::ArmJointPosition& ros_msg, bosdyn::api::ArmJointPosition& proto); /////////////////////////////////////////////////////////////////////////////// // Protobuf to ROS. -void convertToRos(const bosdyn::api::RequestHeader& proto, bosdyn_msgs::msg::RequestHeader& ros_msg); +void convertToRos(const bosdyn::api::RequestHeader& proto, bosdyn_api_msgs::msg::RequestHeader& ros_msg); -void convertToRos(const bosdyn::api::CommonError& proto, bosdyn_msgs::msg::CommonError& ros_msg); +void convertToRos(const bosdyn::api::CommonError& proto, bosdyn_api_msgs::msg::CommonError& ros_msg); -void convertToRos(const bosdyn::api::ResponseHeader& proto, bosdyn_msgs::msg::ResponseHeader& ros_msg); +void convertToRos(const bosdyn::api::ResponseHeader& proto, bosdyn_api_msgs::msg::ResponseHeader& ros_msg); void convertToRos(const google::protobuf::Timestamp& proto, builtin_interfaces::msg::Time& ros_msg); diff --git a/spot_driver/include/spot_driver/conversions/kinematic_conversions.hpp b/spot_driver/include/spot_driver/conversions/kinematic_conversions.hpp index 3c60db4f5..ca9f2b2b0 100644 --- a/spot_driver/include/spot_driver/conversions/kinematic_conversions.hpp +++ b/spot_driver/include/spot_driver/conversions/kinematic_conversions.hpp @@ -4,57 +4,57 @@ #include -#include -#include +#include +#include namespace spot_ros2 { /////////////////////////////////////////////////////////////////////////////// // ROS to Protobuf. -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestFixedStance& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::FixedStance& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOnGroundPlaneStance& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOnGroundPlaneStance& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::OnGroundPlaneStance& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestWristMountedTool& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestWristMountedTool& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::WristMountedTool& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestBodyMountedTool& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestBodyMountedTool& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::BodyMountedTool& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestToolPoseTask& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolPoseTask& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::ToolPoseTask& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestToolGazeTask& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolGazeTask& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::ToolGazeTask& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto); -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequest& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequest& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto); /////////////////////////////////////////////////////////////////////////////// // Protobuf to ROS. -void convertToRos(const bosdyn::api::JointState& proto, bosdyn_msgs::msg::JointState& ros_msg); +void convertToRos(const bosdyn::api::JointState& proto, bosdyn_api_msgs::msg::JointState& ros_msg); void convertToRos(const bosdyn::api::FrameTreeSnapshot::ParentEdge& proto, - bosdyn_msgs::msg::FrameTreeSnapshotParentEdge& ros_msg); + bosdyn_api_msgs::msg::FrameTreeSnapshotParentEdge& ros_msg); -void convertToRos(const bosdyn::api::FrameTreeSnapshot& proto, bosdyn_msgs::msg::FrameTreeSnapshot& ros_msg); +void convertToRos(const bosdyn::api::FrameTreeSnapshot& proto, bosdyn_api_msgs::msg::FrameTreeSnapshot& ros_msg); -void convertToRos(const bosdyn::api::KinematicState& proto, bosdyn_msgs::msg::KinematicState& ros_msg); +void convertToRos(const bosdyn::api::KinematicState& proto, bosdyn_api_msgs::msg::KinematicState& ros_msg); void convertToRos(const bosdyn::api::spot::InverseKinematicsResponse& proto, - bosdyn_msgs::msg::InverseKinematicsResponse& ros_msg); + bosdyn_spot_api_msgs::msg::InverseKinematicsResponse& ros_msg); } // namespace spot_ros2 diff --git a/spot_driver/include/spot_driver/conversions/robot_state.hpp b/spot_driver/include/spot_driver/conversions/robot_state.hpp index 624e03dc8..0391b7634 100644 --- a/spot_driver/include/spot_driver/conversions/robot_state.hpp +++ b/spot_driver/include/spot_driver/conversions/robot_state.hpp @@ -3,7 +3,7 @@ #pragma once #include -#include +#include #include #include #include @@ -162,7 +162,7 @@ std::optional getSystemFaultState(const ::bosd * @return If the robot state message contains data about Spot's manipulator state, return a ManipulatorState message * containing this data. Otherwise, return nullopt. */ -std::optional getManipulatorState(const ::bosdyn::api::RobotState& robot_state); +std::optional getManipulatorState(const ::bosdyn::api::RobotState& robot_state); /** * @brief Create a Vector3Stamped ROS message representing the force exerted on Spot's end effector by parsing a diff --git a/spot_driver/include/spot_driver/robot_state/state_middleware_handle.hpp b/spot_driver/include/spot_driver/robot_state/state_middleware_handle.hpp index 3555f82b7..45b524d43 100644 --- a/spot_driver/include/spot_driver/robot_state/state_middleware_handle.hpp +++ b/spot_driver/include/spot_driver/robot_state/state_middleware_handle.hpp @@ -61,7 +61,7 @@ class StateMiddlewareHandle : public StatePublisher::MiddlewareHandle { std::shared_ptr> odom_publisher_; std::shared_ptr> power_state_publisher_; std::shared_ptr> system_faults_publisher_; - std::shared_ptr> manipulator_state_publisher_; + std::shared_ptr> manipulator_state_publisher_; std::shared_ptr> end_effector_force_publisher_; std::shared_ptr> behavior_fault_state_publisher_; }; diff --git a/spot_driver/include/spot_driver/types.hpp b/spot_driver/include/spot_driver/types.hpp index abd2eb658..f30f312f2 100644 --- a/spot_driver/include/spot_driver/types.hpp +++ b/spot_driver/include/spot_driver/types.hpp @@ -2,7 +2,7 @@ #pragma once -#include +#include #include #include #include @@ -89,7 +89,7 @@ struct RobotStateMessages { std::optional maybe_odom; std::optional maybe_power_state; std::optional maybe_system_fault_state; - std::optional maybe_manipulator_state; + std::optional maybe_manipulator_state; std::optional maybe_end_effector_force; std::optional maybe_behavior_fault_state; }; diff --git a/spot_driver/package.xml b/spot_driver/package.xml index 426b8e56c..eebf3b307 100644 --- a/spot_driver/package.xml +++ b/spot_driver/package.xml @@ -11,28 +11,28 @@ ament_cmake_python rosidl_default_generators - bdai_ros2_wrappers bosdyn + bosdyn_msgs common_interfaces depth_image_proc geometry_msgs nav_msgs protobuf - python3-protobuf rclcpp rclcpp_components - rclpy - robot_state_publisher rosidl_default_runtime - rviz2 sensor_msgs - spot_description spot_msgs - spot_wrapper tf2_ros tl_expected - xacro + bdai_ros2_wrappers + python3-protobuf + robot_state_publisher + rviz2 + spot_description + spot_wrapper + xacro ament_cmake_gmock diff --git a/spot_driver/spot_driver/conversions.py b/spot_driver/spot_driver/conversions.py deleted file mode 100644 index 208a1d733..000000000 --- a/spot_driver/spot_driver/conversions.py +++ /dev/null @@ -1,21004 +0,0 @@ -################ AUTOMATICALLY CREATED FILE DO NOT MODIFY ############ - -# fmt: off -# ruff: noqa -# type: ignore -from spot_driver.manual_conversions import * - - -def convert_bosdyn_msgs_mobility_params_to_any_proto(ros_msg: "bosdyn_msgs.msgs.MobilityParams", proto: "google.protobuf.any_pb2.Any") -> None: - from bosdyn.api.spot.robot_command_pb2 import MobilityParams - raw_proto = MobilityParams() - convert_bosdyn_msgs_mobility_params_to_proto(ros_msg, raw_proto) - proto.Pack(raw_proto) - - -def convert_any_proto_to_bosdyn_msgs_mobility_params(proto: "google.protobuf.any_pb2.Any", ros_msg: "bosdyn_msgs.msgs.MobilityParams") -> None: - from bosdyn.api.spot.robot_command_pb2 import MobilityParams - raw_proto = MobilityParams() - proto.Unpack(raw_proto) - convert_proto_to_bosdyn_msgs_mobility_params(raw_proto, ros_msg) - - -def convert_proto_to_serialized_bosdyn_msgs_dict_param_spec(proto: "bosdyn.api.service_customization_pb2.DictParam.Spec", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import DictParamSpec - full_msg = DictParamSpec() - convert_proto_to_bosdyn_msgs_dict_param_spec(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_dict_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.service_customization_pb2.DictParam.Spec") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import DictParamSpec - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), DictParamSpec) - convert_bosdyn_msgs_dict_param_spec_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_custom_param_spec(proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import CustomParamSpec - full_msg = CustomParamSpec() - convert_proto_to_bosdyn_msgs_custom_param_spec(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_custom_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import CustomParamSpec - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), CustomParamSpec) - convert_bosdyn_msgs_custom_param_spec_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_dict_param(proto: "bosdyn.api.service_customization_pb2.DictParam", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import DictParam - full_msg = DictParam() - convert_proto_to_bosdyn_msgs_dict_param(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_dict_param_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.service_customization_pb2.DictParam") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import DictParam - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), DictParam) - convert_bosdyn_msgs_dict_param_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_custom_param(proto: "bosdyn.api.service_customization_pb2.CustomParam", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import CustomParam - full_msg = CustomParam() - convert_proto_to_bosdyn_msgs_custom_param(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_custom_param_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.service_customization_pb2.CustomParam") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import CustomParam - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), CustomParam) - convert_bosdyn_msgs_custom_param_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_key_string_value_bosdyn_msgs_dict_param(proto: "bosdyn.api.service_customization_pb2.DictParam", ros_msg: "bosdyn_msgs.msgs.KeyStringValueBosdynMsgsSerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsDictParam - full_msg = KeyStringValueBosdynMsgsDictParam() - convert_proto_to_bosdyn_msgs_key_string_value_bosdyn_msgs_dict_param(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_key_string_value_bosdyn_msgs_dict_param_to_proto(ros_msg: "bosdyn_msgs.msgs.KeyStringValueBosdynMsgsSerializedMessage", proto: "bosdyn.api.service_customization_pb2.DictParam") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsDictParam - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), KeyStringValueBosdynMsgsDictParam) - convert_bosdyn_msgs_key_string_value_bosdyn_msgs_dict_param_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_action_wrapper_gripper_camera_params(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCameraParams", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import ActionWrapperGripperCameraParams - full_msg = ActionWrapperGripperCameraParams() - convert_proto_to_bosdyn_msgs_action_wrapper_gripper_camera_params(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_action_wrapper_gripper_camera_params_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCameraParams") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import ActionWrapperGripperCameraParams - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), ActionWrapperGripperCameraParams) - convert_bosdyn_msgs_action_wrapper_gripper_camera_params_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_resource_tree(proto: "bosdyn.api.lease_pb2.ResourceTree", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import ResourceTree - full_msg = ResourceTree() - convert_proto_to_bosdyn_msgs_resource_tree(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_resource_tree_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.lease_pb2.ResourceTree") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import ResourceTree - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), ResourceTree) - convert_bosdyn_msgs_resource_tree_to_proto(full_msg, proto) - - -def convert_proto_to_serialized_bosdyn_msgs_node_info(proto: "bosdyn.api.mission.mission_pb2.NodeInfo", ros_msg: "bosdyn_msgs.msgs.SerializedMessage") -> None: - import rclpy.serialization - from bosdyn_msgs.msg import NodeInfo - full_msg = NodeInfo() - convert_proto_to_bosdyn_msgs_node_info(proto, full_msg) - ros_msg.serialized_msg = list(rclpy.serialization.serialize_message(full_msg)) - - -def convert_serialized_bosdyn_msgs_node_info_to_proto(ros_msg: "bosdyn_msgs.msgs.SerializedMessage", proto: "bosdyn.api.mission.mission_pb2.NodeInfo") -> None: - proto.Clear() - import rclpy.serialization - from bosdyn_msgs.msg import NodeInfo - full_msg = rclpy.serialization.deserialize_message(bytes(ros_msg.serialized_msg), NodeInfo) - convert_bosdyn_msgs_node_info_to_proto(full_msg, proto) - - -def convert_proto_to_bosdyn_msgs_alert_data_severity_level(proto: "bosdyn.api.alerts_pb2.AlertData.SeverityLevel", ros_msg: "bosdyn_msgs.msgs.AlertDataSeverityLevel") -> None: - pass - - -def convert_bosdyn_msgs_alert_data_severity_level_to_proto(ros_msg: "bosdyn_msgs.msgs.AlertDataSeverityLevel", proto: "bosdyn.api.alerts_pb2.AlertData.SeverityLevel") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_alert_data(proto: "bosdyn.api.alerts_pb2.AlertData", ros_msg: "bosdyn_msgs.msgs.AlertData") -> None: - ros_msg.severity.value = proto.severity - ros_msg.title = proto.title - ros_msg.source = proto.source - - -def convert_bosdyn_msgs_alert_data_to_proto(ros_msg: "bosdyn_msgs.msgs.AlertData", proto: "bosdyn.api.alerts_pb2.AlertData") -> None: - proto.Clear() - proto.severity = ros_msg.severity.value - proto.title = ros_msg.title - proto.source = ros_msg.source - - -def convert_proto_to_bosdyn_msgs_arm_command_request_one_of_command(proto: "bosdyn.api.arm_command_pb2.ArmCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmCommandRequestOneOfCommand") -> None: - if proto.HasField("arm_cartesian_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_CARTESIAN_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_cartesian_command_request(proto.arm_cartesian_command, ros_msg.arm_cartesian_command) - if proto.HasField("arm_joint_move_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_JOINT_MOVE_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_joint_move_command_request(proto.arm_joint_move_command, ros_msg.arm_joint_move_command) - if proto.HasField("named_arm_position_command"): - ros_msg.command_choice = ros_msg.COMMAND_NAMED_ARM_POSITION_COMMAND_SET - convert_proto_to_bosdyn_msgs_named_arm_positions_command_request(proto.named_arm_position_command, ros_msg.named_arm_position_command) - if proto.HasField("arm_velocity_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_VELOCITY_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_velocity_command_request(proto.arm_velocity_command, ros_msg.arm_velocity_command) - if proto.HasField("arm_gaze_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_GAZE_COMMAND_SET - convert_proto_to_bosdyn_msgs_gaze_command_request(proto.arm_gaze_command, ros_msg.arm_gaze_command) - if proto.HasField("arm_stop_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_STOP_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_stop_command_request(proto.arm_stop_command, ros_msg.arm_stop_command) - if proto.HasField("arm_drag_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_DRAG_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_drag_command_request(proto.arm_drag_command, ros_msg.arm_drag_command) - if proto.HasField("arm_impedance_command"): - ros_msg.command_choice = ros_msg.COMMAND_ARM_IMPEDANCE_COMMAND_SET - convert_proto_to_bosdyn_msgs_arm_impedance_command_request(proto.arm_impedance_command, ros_msg.arm_impedance_command) - - -def convert_bosdyn_msgs_arm_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCommandRequestOneOfCommand", proto: "bosdyn.api.arm_command_pb2.ArmCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_ARM_CARTESIAN_COMMAND_SET: - convert_bosdyn_msgs_arm_cartesian_command_request_to_proto(ros_msg.arm_cartesian_command, proto.arm_cartesian_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_JOINT_MOVE_COMMAND_SET: - convert_bosdyn_msgs_arm_joint_move_command_request_to_proto(ros_msg.arm_joint_move_command, proto.arm_joint_move_command) - if ros_msg.command_choice == ros_msg.COMMAND_NAMED_ARM_POSITION_COMMAND_SET: - convert_bosdyn_msgs_named_arm_positions_command_request_to_proto(ros_msg.named_arm_position_command, proto.named_arm_position_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_VELOCITY_COMMAND_SET: - convert_bosdyn_msgs_arm_velocity_command_request_to_proto(ros_msg.arm_velocity_command, proto.arm_velocity_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_GAZE_COMMAND_SET: - convert_bosdyn_msgs_gaze_command_request_to_proto(ros_msg.arm_gaze_command, proto.arm_gaze_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_STOP_COMMAND_SET: - convert_bosdyn_msgs_arm_stop_command_request_to_proto(ros_msg.arm_stop_command, proto.arm_stop_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_DRAG_COMMAND_SET: - convert_bosdyn_msgs_arm_drag_command_request_to_proto(ros_msg.arm_drag_command, proto.arm_drag_command) - if ros_msg.command_choice == ros_msg.COMMAND_ARM_IMPEDANCE_COMMAND_SET: - convert_bosdyn_msgs_arm_impedance_command_request_to_proto(ros_msg.arm_impedance_command, proto.arm_impedance_command) - - -def convert_proto_to_bosdyn_msgs_arm_command_request(proto: "bosdyn.api.arm_command_pb2.ArmCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_arm_command_request_one_of_command(proto, ros_msg.command) - convert_proto_to_bosdyn_msgs_arm_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_arm_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_arm_command_request_one_of_command_to_proto(ros_msg.command, proto) - if ros_msg.params_is_set: - convert_bosdyn_msgs_arm_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_arm_command_feedback_one_of_feedback(proto: "bosdyn.api.arm_command_pb2.ArmCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmCommandFeedbackOneOfFeedback") -> None: - if proto.HasField("arm_cartesian_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_CARTESIAN_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_cartesian_command_feedback(proto.arm_cartesian_feedback, ros_msg.arm_cartesian_feedback) - if proto.HasField("arm_joint_move_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_JOINT_MOVE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_joint_move_command_feedback(proto.arm_joint_move_feedback, ros_msg.arm_joint_move_feedback) - if proto.HasField("named_arm_position_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_NAMED_ARM_POSITION_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_named_arm_positions_command_feedback(proto.named_arm_position_feedback, ros_msg.named_arm_position_feedback) - if proto.HasField("arm_velocity_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_VELOCITY_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_velocity_command_feedback(proto.arm_velocity_feedback, ros_msg.arm_velocity_feedback) - if proto.HasField("arm_gaze_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_GAZE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_gaze_command_feedback(proto.arm_gaze_feedback, ros_msg.arm_gaze_feedback) - if proto.HasField("arm_stop_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_STOP_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_stop_command_feedback(proto.arm_stop_feedback, ros_msg.arm_stop_feedback) - if proto.HasField("arm_drag_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_DRAG_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_drag_command_feedback(proto.arm_drag_feedback, ros_msg.arm_drag_feedback) - if proto.HasField("arm_impedance_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_ARM_IMPEDANCE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_arm_impedance_command_feedback(proto.arm_impedance_feedback, ros_msg.arm_impedance_feedback) - - -def convert_bosdyn_msgs_arm_command_feedback_one_of_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCommandFeedbackOneOfFeedback", proto: "bosdyn.api.arm_command_pb2.ArmCommand.Feedback") -> None: - proto.ClearField("feedback") - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_CARTESIAN_FEEDBACK_SET: - convert_bosdyn_msgs_arm_cartesian_command_feedback_to_proto(ros_msg.arm_cartesian_feedback, proto.arm_cartesian_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_JOINT_MOVE_FEEDBACK_SET: - convert_bosdyn_msgs_arm_joint_move_command_feedback_to_proto(ros_msg.arm_joint_move_feedback, proto.arm_joint_move_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_NAMED_ARM_POSITION_FEEDBACK_SET: - convert_bosdyn_msgs_named_arm_positions_command_feedback_to_proto(ros_msg.named_arm_position_feedback, proto.named_arm_position_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_VELOCITY_FEEDBACK_SET: - convert_bosdyn_msgs_arm_velocity_command_feedback_to_proto(ros_msg.arm_velocity_feedback, proto.arm_velocity_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_GAZE_FEEDBACK_SET: - convert_bosdyn_msgs_gaze_command_feedback_to_proto(ros_msg.arm_gaze_feedback, proto.arm_gaze_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_STOP_FEEDBACK_SET: - convert_bosdyn_msgs_arm_stop_command_feedback_to_proto(ros_msg.arm_stop_feedback, proto.arm_stop_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_DRAG_FEEDBACK_SET: - convert_bosdyn_msgs_arm_drag_command_feedback_to_proto(ros_msg.arm_drag_feedback, proto.arm_drag_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_ARM_IMPEDANCE_FEEDBACK_SET: - convert_bosdyn_msgs_arm_impedance_command_feedback_to_proto(ros_msg.arm_impedance_feedback, proto.arm_impedance_feedback) - - -def convert_proto_to_bosdyn_msgs_arm_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_arm_command_feedback_one_of_feedback(proto, ros_msg.feedback) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_arm_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmCommand.Feedback") -> None: - proto.Clear() - convert_bosdyn_msgs_arm_command_feedback_one_of_feedback_to_proto(ros_msg.feedback, proto) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_arm_command(proto: "bosdyn.api.arm_command_pb2.ArmCommand", ros_msg: "bosdyn_msgs.msgs.ArmCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCommand", proto: "bosdyn.api.arm_command_pb2.ArmCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_params(proto: "bosdyn.api.arm_command_pb2.ArmParams", ros_msg: "bosdyn_msgs.msgs.ArmParams") -> None: - ros_msg.disable_body_force_limiter = proto.disable_body_force_limiter.value - ros_msg.disable_body_force_limiter_is_set = proto.HasField("disable_body_force_limiter") - - -def convert_bosdyn_msgs_arm_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmParams", proto: "bosdyn.api.arm_command_pb2.ArmParams") -> None: - proto.Clear() - if ros_msg.disable_body_force_limiter_is_set: - convert_bool_to_proto(ros_msg.disable_body_force_limiter, proto.disable_body_force_limiter) - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command_cylindrical_velocity(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.CylindricalVelocity", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandCylindricalVelocity") -> None: - convert_proto_to_bosdyn_msgs_cylindrical_coordinate(proto.linear_velocity, ros_msg.linear_velocity) - ros_msg.linear_velocity_is_set = proto.HasField("linear_velocity") - ros_msg.max_linear_velocity = proto.max_linear_velocity.value - ros_msg.max_linear_velocity_is_set = proto.HasField("max_linear_velocity") - - -def convert_bosdyn_msgs_arm_velocity_command_cylindrical_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandCylindricalVelocity", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.CylindricalVelocity") -> None: - proto.Clear() - if ros_msg.linear_velocity_is_set: - convert_bosdyn_msgs_cylindrical_coordinate_to_proto(ros_msg.linear_velocity, proto.linear_velocity) - if ros_msg.max_linear_velocity_is_set: - convert_float64_to_proto(ros_msg.max_linear_velocity, proto.max_linear_velocity) - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command_cartesian_velocity(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.CartesianVelocity", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandCartesianVelocity") -> None: - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.velocity_in_frame_name, ros_msg.velocity_in_frame_name) - ros_msg.velocity_in_frame_name_is_set = proto.HasField("velocity_in_frame_name") - - -def convert_bosdyn_msgs_arm_velocity_command_cartesian_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandCartesianVelocity", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.CartesianVelocity") -> None: - proto.Clear() - proto.frame_name = ros_msg.frame_name - if ros_msg.velocity_in_frame_name_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.velocity_in_frame_name, proto.velocity_in_frame_name) - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command_request_one_of_command(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandRequestOneOfCommand") -> None: - if proto.HasField("cylindrical_velocity"): - ros_msg.command_choice = ros_msg.COMMAND_CYLINDRICAL_VELOCITY_SET - convert_proto_to_bosdyn_msgs_arm_velocity_command_cylindrical_velocity(proto.cylindrical_velocity, ros_msg.cylindrical_velocity) - if proto.HasField("cartesian_velocity"): - ros_msg.command_choice = ros_msg.COMMAND_CARTESIAN_VELOCITY_SET - convert_proto_to_bosdyn_msgs_arm_velocity_command_cartesian_velocity(proto.cartesian_velocity, ros_msg.cartesian_velocity) - - -def convert_bosdyn_msgs_arm_velocity_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandRequestOneOfCommand", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_CYLINDRICAL_VELOCITY_SET: - convert_bosdyn_msgs_arm_velocity_command_cylindrical_velocity_to_proto(ros_msg.cylindrical_velocity, proto.cylindrical_velocity) - if ros_msg.command_choice == ros_msg.COMMAND_CARTESIAN_VELOCITY_SET: - convert_bosdyn_msgs_arm_velocity_command_cartesian_velocity_to_proto(ros_msg.cartesian_velocity, proto.cartesian_velocity) - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command_request(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_arm_velocity_command_request_one_of_command(proto, ros_msg.command) - convert_proto_to_geometry_msgs_vector3(proto.angular_velocity_of_hand_rt_odom_in_hand, ros_msg.angular_velocity_of_hand_rt_odom_in_hand) - ros_msg.angular_velocity_of_hand_rt_odom_in_hand_is_set = proto.HasField("angular_velocity_of_hand_rt_odom_in_hand") - ros_msg.maximum_acceleration = proto.maximum_acceleration.value - ros_msg.maximum_acceleration_is_set = proto.HasField("maximum_acceleration") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - - -def convert_bosdyn_msgs_arm_velocity_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_arm_velocity_command_request_one_of_command_to_proto(ros_msg.command, proto) - if ros_msg.angular_velocity_of_hand_rt_odom_in_hand_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.angular_velocity_of_hand_rt_odom_in_hand, proto.angular_velocity_of_hand_rt_odom_in_hand) - if ros_msg.maximum_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_acceleration, proto.maximum_acceleration) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_arm_velocity_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_velocity_command(proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand", ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_velocity_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmVelocityCommand", proto: "bosdyn.api.arm_command_pb2.ArmVelocityCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_named_arm_positions_command_positions(proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Positions", ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandPositions") -> None: - pass - - -def convert_bosdyn_msgs_named_arm_positions_command_positions_to_proto(ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandPositions", proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Positions") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_named_arm_positions_command_request(proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Request", ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandRequest") -> None: - ros_msg.position.value = proto.position - - -def convert_bosdyn_msgs_named_arm_positions_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandRequest", proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Request") -> None: - proto.Clear() - proto.position = ros_msg.position.value - - -def convert_proto_to_bosdyn_msgs_named_arm_positions_command_feedback_status(proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_named_arm_positions_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandFeedbackStatus", proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_named_arm_positions_command_feedback(proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_named_arm_positions_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommandFeedback", proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_named_arm_positions_command(proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand", ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommand") -> None: - pass - - -def convert_bosdyn_msgs_named_arm_positions_command_to_proto(ros_msg: "bosdyn_msgs.msgs.NamedArmPositionsCommand", proto: "bosdyn.api.arm_command_pb2.NamedArmPositionsCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command_request_one_of_joint_configuration(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequestOneOfJointConfiguration") -> None: - if proto.HasField("force_remain_near_current_joint_configuration"): - ros_msg.joint_configuration_choice = ros_msg.JOINT_CONFIGURATION_FORCE_REMAIN_NEAR_CURRENT_JOINT_CONFIGURATION_SET - ros_msg.force_remain_near_current_joint_configuration = proto.force_remain_near_current_joint_configuration - if proto.HasField("preferred_joint_configuration"): - ros_msg.joint_configuration_choice = ros_msg.JOINT_CONFIGURATION_PREFERRED_JOINT_CONFIGURATION_SET - convert_proto_to_bosdyn_msgs_arm_joint_position(proto.preferred_joint_configuration, ros_msg.preferred_joint_configuration) - - -def convert_bosdyn_msgs_arm_cartesian_command_request_one_of_joint_configuration_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequestOneOfJointConfiguration", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request") -> None: - proto.ClearField("joint_configuration") - if ros_msg.joint_configuration_choice == ros_msg.JOINT_CONFIGURATION_FORCE_REMAIN_NEAR_CURRENT_JOINT_CONFIGURATION_SET: - proto.force_remain_near_current_joint_configuration = ros_msg.force_remain_near_current_joint_configuration - if ros_msg.joint_configuration_choice == ros_msg.JOINT_CONFIGURATION_PREFERRED_JOINT_CONFIGURATION_SET: - convert_bosdyn_msgs_arm_joint_position_to_proto(ros_msg.preferred_joint_configuration, proto.preferred_joint_configuration) - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command_request_axis_mode(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request.AxisMode", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequestAxisMode") -> None: - pass - - -def convert_bosdyn_msgs_arm_cartesian_command_request_axis_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequestAxisMode", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request.AxisMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command_request(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequest") -> None: - ros_msg.root_frame_name = proto.root_frame_name - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - convert_proto_to_geometry_msgs_pose(proto.root_tform_task, ros_msg.root_tform_task) - ros_msg.root_tform_task_is_set = proto.HasField("root_tform_task") - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.pose_trajectory_in_task, ros_msg.pose_trajectory_in_task) - ros_msg.pose_trajectory_in_task_is_set = proto.HasField("pose_trajectory_in_task") - ros_msg.maximum_acceleration = proto.maximum_acceleration.value - ros_msg.maximum_acceleration_is_set = proto.HasField("maximum_acceleration") - ros_msg.max_linear_velocity = proto.max_linear_velocity.value - ros_msg.max_linear_velocity_is_set = proto.HasField("max_linear_velocity") - ros_msg.max_angular_velocity = proto.max_angular_velocity.value - ros_msg.max_angular_velocity_is_set = proto.HasField("max_angular_velocity") - ros_msg.max_pos_tracking_error = proto.max_pos_tracking_error.value - ros_msg.max_pos_tracking_error_is_set = proto.HasField("max_pos_tracking_error") - ros_msg.max_rot_tracking_error = proto.max_rot_tracking_error.value - ros_msg.max_rot_tracking_error_is_set = proto.HasField("max_rot_tracking_error") - convert_proto_to_bosdyn_msgs_arm_cartesian_command_request_one_of_joint_configuration(proto, ros_msg.joint_configuration) - ros_msg.x_axis.value = proto.x_axis - ros_msg.y_axis.value = proto.y_axis - ros_msg.z_axis.value = proto.z_axis - ros_msg.rx_axis.value = proto.rx_axis - ros_msg.ry_axis.value = proto.ry_axis - ros_msg.rz_axis.value = proto.rz_axis - convert_proto_to_bosdyn_msgs_wrench_trajectory(proto.wrench_trajectory_in_task, ros_msg.wrench_trajectory_in_task) - ros_msg.wrench_trajectory_in_task_is_set = proto.HasField("wrench_trajectory_in_task") - - -def convert_bosdyn_msgs_arm_cartesian_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Request") -> None: - proto.Clear() - proto.root_frame_name = ros_msg.root_frame_name - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - if ros_msg.root_tform_task_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.root_tform_task, proto.root_tform_task) - if ros_msg.pose_trajectory_in_task_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.pose_trajectory_in_task, proto.pose_trajectory_in_task) - if ros_msg.maximum_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_acceleration, proto.maximum_acceleration) - if ros_msg.max_linear_velocity_is_set: - convert_float64_to_proto(ros_msg.max_linear_velocity, proto.max_linear_velocity) - if ros_msg.max_angular_velocity_is_set: - convert_float64_to_proto(ros_msg.max_angular_velocity, proto.max_angular_velocity) - if ros_msg.max_pos_tracking_error_is_set: - convert_float64_to_proto(ros_msg.max_pos_tracking_error, proto.max_pos_tracking_error) - if ros_msg.max_rot_tracking_error_is_set: - convert_float64_to_proto(ros_msg.max_rot_tracking_error, proto.max_rot_tracking_error) - convert_bosdyn_msgs_arm_cartesian_command_request_one_of_joint_configuration_to_proto(ros_msg.joint_configuration, proto) - proto.x_axis = ros_msg.x_axis.value - proto.y_axis = ros_msg.y_axis.value - proto.z_axis = ros_msg.z_axis.value - proto.rx_axis = ros_msg.rx_axis.value - proto.ry_axis = ros_msg.ry_axis.value - proto.rz_axis = ros_msg.rz_axis.value - if ros_msg.wrench_trajectory_in_task_is_set: - convert_bosdyn_msgs_wrench_trajectory_to_proto(ros_msg.wrench_trajectory_in_task, proto.wrench_trajectory_in_task) - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command_feedback_status(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_arm_cartesian_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandFeedbackStatus", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.measured_pos_tracking_error = proto.measured_pos_tracking_error - ros_msg.measured_rot_tracking_error = proto.measured_rot_tracking_error - ros_msg.measured_pos_distance_to_goal = proto.measured_pos_distance_to_goal - ros_msg.measured_rot_distance_to_goal = proto.measured_rot_distance_to_goal - - -def convert_bosdyn_msgs_arm_cartesian_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.measured_pos_tracking_error = ros_msg.measured_pos_tracking_error - proto.measured_rot_tracking_error = ros_msg.measured_rot_tracking_error - proto.measured_pos_distance_to_goal = ros_msg.measured_pos_distance_to_goal - proto.measured_rot_distance_to_goal = ros_msg.measured_rot_distance_to_goal - - -def convert_proto_to_bosdyn_msgs_arm_cartesian_command(proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand", ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_cartesian_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmCartesianCommand", proto: "bosdyn.api.arm_command_pb2.ArmCartesianCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_joint_move_command_request(proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_arm_joint_trajectory(proto.trajectory, ros_msg.trajectory) - ros_msg.trajectory_is_set = proto.HasField("trajectory") - - -def convert_bosdyn_msgs_arm_joint_move_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Request") -> None: - proto.Clear() - if ros_msg.trajectory_is_set: - convert_bosdyn_msgs_arm_joint_trajectory_to_proto(ros_msg.trajectory, proto.trajectory) - - -def convert_proto_to_bosdyn_msgs_arm_joint_move_command_feedback_status(proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_arm_joint_move_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedbackStatus", proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_joint_move_command_feedback_planner_status(proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback.PlannerStatus", ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedbackPlannerStatus") -> None: - pass - - -def convert_bosdyn_msgs_arm_joint_move_command_feedback_planner_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedbackPlannerStatus", proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback.PlannerStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_joint_move_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.planner_status.value = proto.planner_status - from bosdyn_msgs.msg import ArmJointTrajectoryPoint - ros_msg.planned_points = [] - for _item in proto.planned_points: - ros_msg.planned_points.append(ArmJointTrajectoryPoint()) - convert_proto_to_bosdyn_msgs_arm_joint_trajectory_point(_item, ros_msg.planned_points[-1]) - convert_proto_to_builtin_interfaces_duration(proto.time_to_goal, ros_msg.time_to_goal) - ros_msg.time_to_goal_is_set = proto.HasField("time_to_goal") - - -def convert_bosdyn_msgs_arm_joint_move_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.planner_status = ros_msg.planner_status.value - del proto.planned_points[:] - for _item in ros_msg.planned_points: - convert_bosdyn_msgs_arm_joint_trajectory_point_to_proto(_item, proto.planned_points.add()) - if ros_msg.time_to_goal_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_to_goal, proto.time_to_goal) - - -def convert_proto_to_bosdyn_msgs_arm_joint_move_command(proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand", ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_joint_move_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointMoveCommand", proto: "bosdyn.api.arm_command_pb2.ArmJointMoveCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_joint_position(proto: "bosdyn.api.arm_command_pb2.ArmJointPosition", ros_msg: "bosdyn_msgs.msgs.ArmJointPosition") -> None: - ros_msg.sh0 = proto.sh0.value - ros_msg.sh0_is_set = proto.HasField("sh0") - ros_msg.sh1 = proto.sh1.value - ros_msg.sh1_is_set = proto.HasField("sh1") - ros_msg.el0 = proto.el0.value - ros_msg.el0_is_set = proto.HasField("el0") - ros_msg.el1 = proto.el1.value - ros_msg.el1_is_set = proto.HasField("el1") - ros_msg.wr0 = proto.wr0.value - ros_msg.wr0_is_set = proto.HasField("wr0") - ros_msg.wr1 = proto.wr1.value - ros_msg.wr1_is_set = proto.HasField("wr1") - - -def convert_bosdyn_msgs_arm_joint_position_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointPosition", proto: "bosdyn.api.arm_command_pb2.ArmJointPosition") -> None: - proto.Clear() - if ros_msg.sh0_is_set: - convert_float64_to_proto(ros_msg.sh0, proto.sh0) - if ros_msg.sh1_is_set: - convert_float64_to_proto(ros_msg.sh1, proto.sh1) - if ros_msg.el0_is_set: - convert_float64_to_proto(ros_msg.el0, proto.el0) - if ros_msg.el1_is_set: - convert_float64_to_proto(ros_msg.el1, proto.el1) - if ros_msg.wr0_is_set: - convert_float64_to_proto(ros_msg.wr0, proto.wr0) - if ros_msg.wr1_is_set: - convert_float64_to_proto(ros_msg.wr1, proto.wr1) - - -def convert_proto_to_bosdyn_msgs_arm_joint_velocity(proto: "bosdyn.api.arm_command_pb2.ArmJointVelocity", ros_msg: "bosdyn_msgs.msgs.ArmJointVelocity") -> None: - ros_msg.sh0 = proto.sh0.value - ros_msg.sh0_is_set = proto.HasField("sh0") - ros_msg.sh1 = proto.sh1.value - ros_msg.sh1_is_set = proto.HasField("sh1") - ros_msg.el0 = proto.el0.value - ros_msg.el0_is_set = proto.HasField("el0") - ros_msg.el1 = proto.el1.value - ros_msg.el1_is_set = proto.HasField("el1") - ros_msg.wr0 = proto.wr0.value - ros_msg.wr0_is_set = proto.HasField("wr0") - ros_msg.wr1 = proto.wr1.value - ros_msg.wr1_is_set = proto.HasField("wr1") - - -def convert_bosdyn_msgs_arm_joint_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointVelocity", proto: "bosdyn.api.arm_command_pb2.ArmJointVelocity") -> None: - proto.Clear() - if ros_msg.sh0_is_set: - convert_float64_to_proto(ros_msg.sh0, proto.sh0) - if ros_msg.sh1_is_set: - convert_float64_to_proto(ros_msg.sh1, proto.sh1) - if ros_msg.el0_is_set: - convert_float64_to_proto(ros_msg.el0, proto.el0) - if ros_msg.el1_is_set: - convert_float64_to_proto(ros_msg.el1, proto.el1) - if ros_msg.wr0_is_set: - convert_float64_to_proto(ros_msg.wr0, proto.wr0) - if ros_msg.wr1_is_set: - convert_float64_to_proto(ros_msg.wr1, proto.wr1) - - -def convert_proto_to_bosdyn_msgs_arm_joint_trajectory_point(proto: "bosdyn.api.arm_command_pb2.ArmJointTrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.ArmJointTrajectoryPoint") -> None: - convert_proto_to_bosdyn_msgs_arm_joint_position(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - convert_proto_to_bosdyn_msgs_arm_joint_velocity(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_arm_joint_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointTrajectoryPoint", proto: "bosdyn.api.arm_command_pb2.ArmJointTrajectoryPoint") -> None: - proto.Clear() - if ros_msg.position_is_set: - convert_bosdyn_msgs_arm_joint_position_to_proto(ros_msg.position, proto.position) - if ros_msg.velocity_is_set: - convert_bosdyn_msgs_arm_joint_velocity_to_proto(ros_msg.velocity, proto.velocity) - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_arm_joint_trajectory(proto: "bosdyn.api.arm_command_pb2.ArmJointTrajectory", ros_msg: "bosdyn_msgs.msgs.ArmJointTrajectory") -> None: - from bosdyn_msgs.msg import ArmJointTrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(ArmJointTrajectoryPoint()) - convert_proto_to_bosdyn_msgs_arm_joint_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - ros_msg.maximum_velocity = proto.maximum_velocity.value - ros_msg.maximum_velocity_is_set = proto.HasField("maximum_velocity") - ros_msg.maximum_acceleration = proto.maximum_acceleration.value - ros_msg.maximum_acceleration_is_set = proto.HasField("maximum_acceleration") - - -def convert_bosdyn_msgs_arm_joint_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmJointTrajectory", proto: "bosdyn.api.arm_command_pb2.ArmJointTrajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_arm_joint_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - if ros_msg.maximum_velocity_is_set: - convert_float64_to_proto(ros_msg.maximum_velocity, proto.maximum_velocity) - if ros_msg.maximum_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_acceleration, proto.maximum_acceleration) - - -def convert_proto_to_bosdyn_msgs_gaze_command_request(proto: "bosdyn.api.arm_command_pb2.GazeCommand.Request", ros_msg: "bosdyn_msgs.msgs.GazeCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_vec3_trajectory(proto.target_trajectory_in_frame1, ros_msg.target_trajectory_in_frame1) - ros_msg.target_trajectory_in_frame1_is_set = proto.HasField("target_trajectory_in_frame1") - ros_msg.frame1_name = proto.frame1_name - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.tool_trajectory_in_frame2, ros_msg.tool_trajectory_in_frame2) - ros_msg.tool_trajectory_in_frame2_is_set = proto.HasField("tool_trajectory_in_frame2") - ros_msg.frame2_name = proto.frame2_name - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - ros_msg.target_trajectory_initial_velocity = proto.target_trajectory_initial_velocity.value - ros_msg.target_trajectory_initial_velocity_is_set = proto.HasField("target_trajectory_initial_velocity") - ros_msg.maximum_acceleration = proto.maximum_acceleration.value - ros_msg.maximum_acceleration_is_set = proto.HasField("maximum_acceleration") - ros_msg.max_linear_velocity = proto.max_linear_velocity.value - ros_msg.max_linear_velocity_is_set = proto.HasField("max_linear_velocity") - ros_msg.max_angular_velocity = proto.max_angular_velocity.value - ros_msg.max_angular_velocity_is_set = proto.HasField("max_angular_velocity") - - -def convert_bosdyn_msgs_gaze_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GazeCommandRequest", proto: "bosdyn.api.arm_command_pb2.GazeCommand.Request") -> None: - proto.Clear() - if ros_msg.target_trajectory_in_frame1_is_set: - convert_bosdyn_msgs_vec3_trajectory_to_proto(ros_msg.target_trajectory_in_frame1, proto.target_trajectory_in_frame1) - proto.frame1_name = ros_msg.frame1_name - if ros_msg.tool_trajectory_in_frame2_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.tool_trajectory_in_frame2, proto.tool_trajectory_in_frame2) - proto.frame2_name = ros_msg.frame2_name - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - if ros_msg.target_trajectory_initial_velocity_is_set: - convert_float64_to_proto(ros_msg.target_trajectory_initial_velocity, proto.target_trajectory_initial_velocity) - if ros_msg.maximum_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_acceleration, proto.maximum_acceleration) - if ros_msg.max_linear_velocity_is_set: - convert_float64_to_proto(ros_msg.max_linear_velocity, proto.max_linear_velocity) - if ros_msg.max_angular_velocity_is_set: - convert_float64_to_proto(ros_msg.max_angular_velocity, proto.max_angular_velocity) - - -def convert_proto_to_bosdyn_msgs_gaze_command_feedback_status(proto: "bosdyn.api.arm_command_pb2.GazeCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.GazeCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_gaze_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GazeCommandFeedbackStatus", proto: "bosdyn.api.arm_command_pb2.GazeCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_gaze_command_feedback(proto: "bosdyn.api.arm_command_pb2.GazeCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.GazeCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.gazing_at_target = proto.gazing_at_target - ros_msg.gaze_to_target_rotation_measured = proto.gaze_to_target_rotation_measured - ros_msg.hand_position_at_goal = proto.hand_position_at_goal - ros_msg.hand_distance_to_goal_measured = proto.hand_distance_to_goal_measured - ros_msg.hand_roll_at_goal = proto.hand_roll_at_goal - ros_msg.hand_roll_to_target_roll_measured = proto.hand_roll_to_target_roll_measured - - -def convert_bosdyn_msgs_gaze_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.GazeCommandFeedback", proto: "bosdyn.api.arm_command_pb2.GazeCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.gazing_at_target = ros_msg.gazing_at_target - proto.gaze_to_target_rotation_measured = ros_msg.gaze_to_target_rotation_measured - proto.hand_position_at_goal = ros_msg.hand_position_at_goal - proto.hand_distance_to_goal_measured = ros_msg.hand_distance_to_goal_measured - proto.hand_roll_at_goal = ros_msg.hand_roll_at_goal - proto.hand_roll_to_target_roll_measured = ros_msg.hand_roll_to_target_roll_measured - - -def convert_proto_to_bosdyn_msgs_gaze_command(proto: "bosdyn.api.arm_command_pb2.GazeCommand", ros_msg: "bosdyn_msgs.msgs.GazeCommand") -> None: - pass - - -def convert_bosdyn_msgs_gaze_command_to_proto(ros_msg: "bosdyn_msgs.msgs.GazeCommand", proto: "bosdyn.api.arm_command_pb2.GazeCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_stop_command_request(proto: "bosdyn.api.arm_command_pb2.ArmStopCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmStopCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_arm_stop_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmStopCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmStopCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_stop_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmStopCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmStopCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_arm_stop_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmStopCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmStopCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_stop_command(proto: "bosdyn.api.arm_command_pb2.ArmStopCommand", ros_msg: "bosdyn_msgs.msgs.ArmStopCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_stop_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmStopCommand", proto: "bosdyn.api.arm_command_pb2.ArmStopCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_impedance_command_request(proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandRequest") -> None: - ros_msg.root_frame_name = proto.root_frame_name - convert_proto_to_geometry_msgs_pose(proto.root_tform_task, ros_msg.root_tform_task) - ros_msg.root_tform_task_is_set = proto.HasField("root_tform_task") - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.task_tform_desired_tool, ros_msg.task_tform_desired_tool) - ros_msg.task_tform_desired_tool_is_set = proto.HasField("task_tform_desired_tool") - convert_proto_to_geometry_msgs_wrench(proto.feed_forward_wrench_at_tool_in_desired_tool, ros_msg.feed_forward_wrench_at_tool_in_desired_tool) - ros_msg.feed_forward_wrench_at_tool_in_desired_tool_is_set = proto.HasField("feed_forward_wrench_at_tool_in_desired_tool") - convert_proto_to_bosdyn_msgs_vector(proto.diagonal_stiffness_matrix, ros_msg.diagonal_stiffness_matrix) - ros_msg.diagonal_stiffness_matrix_is_set = proto.HasField("diagonal_stiffness_matrix") - convert_proto_to_bosdyn_msgs_vector(proto.diagonal_damping_matrix, ros_msg.diagonal_damping_matrix) - ros_msg.diagonal_damping_matrix_is_set = proto.HasField("diagonal_damping_matrix") - ros_msg.max_force_mag = proto.max_force_mag.value - ros_msg.max_force_mag_is_set = proto.HasField("max_force_mag") - ros_msg.max_torque_mag = proto.max_torque_mag.value - ros_msg.max_torque_mag_is_set = proto.HasField("max_torque_mag") - - -def convert_bosdyn_msgs_arm_impedance_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandRequest", proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Request") -> None: - proto.Clear() - proto.root_frame_name = ros_msg.root_frame_name - if ros_msg.root_tform_task_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.root_tform_task, proto.root_tform_task) - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - if ros_msg.task_tform_desired_tool_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.task_tform_desired_tool, proto.task_tform_desired_tool) - if ros_msg.feed_forward_wrench_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.feed_forward_wrench_at_tool_in_desired_tool, proto.feed_forward_wrench_at_tool_in_desired_tool) - if ros_msg.diagonal_stiffness_matrix_is_set: - convert_bosdyn_msgs_vector_to_proto(ros_msg.diagonal_stiffness_matrix, proto.diagonal_stiffness_matrix) - if ros_msg.diagonal_damping_matrix_is_set: - convert_bosdyn_msgs_vector_to_proto(ros_msg.diagonal_damping_matrix, proto.diagonal_damping_matrix) - if ros_msg.max_force_mag_is_set: - convert_float64_to_proto(ros_msg.max_force_mag, proto.max_force_mag) - if ros_msg.max_torque_mag_is_set: - convert_float64_to_proto(ros_msg.max_torque_mag, proto.max_torque_mag) - - -def convert_proto_to_bosdyn_msgs_arm_impedance_command_feedback_status(proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_arm_impedance_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandFeedbackStatus", proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_impedance_command_feedback(proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandFeedback") -> None: - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - convert_proto_to_geometry_msgs_wrench(proto.commanded_wrench_from_stiffness_at_tool_in_desired_tool, ros_msg.commanded_wrench_from_stiffness_at_tool_in_desired_tool) - ros_msg.commanded_wrench_from_stiffness_at_tool_in_desired_tool_is_set = proto.HasField("commanded_wrench_from_stiffness_at_tool_in_desired_tool") - convert_proto_to_geometry_msgs_wrench(proto.commanded_wrench_from_damping_at_tool_in_desired_tool, ros_msg.commanded_wrench_from_damping_at_tool_in_desired_tool) - ros_msg.commanded_wrench_from_damping_at_tool_in_desired_tool_is_set = proto.HasField("commanded_wrench_from_damping_at_tool_in_desired_tool") - convert_proto_to_geometry_msgs_wrench(proto.commanded_wrench_from_feed_forward_at_tool_in_desired_tool, ros_msg.commanded_wrench_from_feed_forward_at_tool_in_desired_tool) - ros_msg.commanded_wrench_from_feed_forward_at_tool_in_desired_tool_is_set = proto.HasField("commanded_wrench_from_feed_forward_at_tool_in_desired_tool") - convert_proto_to_geometry_msgs_wrench(proto.total_commanded_wrench_at_tool_in_desired_tool, ros_msg.total_commanded_wrench_at_tool_in_desired_tool) - ros_msg.total_commanded_wrench_at_tool_in_desired_tool_is_set = proto.HasField("total_commanded_wrench_at_tool_in_desired_tool") - convert_proto_to_geometry_msgs_wrench(proto.total_measured_wrench_at_tool_in_desired_tool, ros_msg.total_measured_wrench_at_tool_in_desired_tool) - ros_msg.total_measured_wrench_at_tool_in_desired_tool_is_set = proto.HasField("total_measured_wrench_at_tool_in_desired_tool") - - -def convert_bosdyn_msgs_arm_impedance_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommandFeedback", proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - if ros_msg.commanded_wrench_from_stiffness_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.commanded_wrench_from_stiffness_at_tool_in_desired_tool, proto.commanded_wrench_from_stiffness_at_tool_in_desired_tool) - if ros_msg.commanded_wrench_from_damping_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.commanded_wrench_from_damping_at_tool_in_desired_tool, proto.commanded_wrench_from_damping_at_tool_in_desired_tool) - if ros_msg.commanded_wrench_from_feed_forward_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.commanded_wrench_from_feed_forward_at_tool_in_desired_tool, proto.commanded_wrench_from_feed_forward_at_tool_in_desired_tool) - if ros_msg.total_commanded_wrench_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.total_commanded_wrench_at_tool_in_desired_tool, proto.total_commanded_wrench_at_tool_in_desired_tool) - if ros_msg.total_measured_wrench_at_tool_in_desired_tool_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.total_measured_wrench_at_tool_in_desired_tool, proto.total_measured_wrench_at_tool_in_desired_tool) - - -def convert_proto_to_bosdyn_msgs_arm_impedance_command(proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand", ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_impedance_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmImpedanceCommand", proto: "bosdyn.api.arm_command_pb2.ArmImpedanceCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_request_one_of_joint_configuration(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestOneOfJointConfiguration") -> None: - if proto.HasField("force_remain_near_current_joint_configuration"): - ros_msg.joint_configuration_choice = ros_msg.JOINT_CONFIGURATION_FORCE_REMAIN_NEAR_CURRENT_JOINT_CONFIGURATION_SET - ros_msg.force_remain_near_current_joint_configuration = proto.force_remain_near_current_joint_configuration - if proto.HasField("preferred_joint_configuration"): - ros_msg.joint_configuration_choice = ros_msg.JOINT_CONFIGURATION_PREFERRED_JOINT_CONFIGURATION_SET - convert_proto_to_bosdyn_msgs_arm_joint_position(proto.preferred_joint_configuration, ros_msg.preferred_joint_configuration) - - -def convert_bosdyn_msgs_arm_surface_contact_request_one_of_joint_configuration_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestOneOfJointConfiguration", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request") -> None: - proto.ClearField("joint_configuration") - if ros_msg.joint_configuration_choice == ros_msg.JOINT_CONFIGURATION_FORCE_REMAIN_NEAR_CURRENT_JOINT_CONFIGURATION_SET: - proto.force_remain_near_current_joint_configuration = ros_msg.force_remain_near_current_joint_configuration - if ros_msg.joint_configuration_choice == ros_msg.JOINT_CONFIGURATION_PREFERRED_JOINT_CONFIGURATION_SET: - convert_bosdyn_msgs_arm_joint_position_to_proto(ros_msg.preferred_joint_configuration, proto.preferred_joint_configuration) - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_request_axis_mode(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request.AxisMode", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestAxisMode") -> None: - pass - - -def convert_bosdyn_msgs_arm_surface_contact_request_axis_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestAxisMode", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request.AxisMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_request_admittance_setting(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request.AdmittanceSetting", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestAdmittanceSetting") -> None: - pass - - -def convert_bosdyn_msgs_arm_surface_contact_request_admittance_setting_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequestAdmittanceSetting", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request.AdmittanceSetting") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_request(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequest") -> None: - ros_msg.root_frame_name = proto.root_frame_name - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - convert_proto_to_geometry_msgs_pose(proto.root_tform_task, ros_msg.root_tform_task) - ros_msg.root_tform_task_is_set = proto.HasField("root_tform_task") - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.pose_trajectory_in_task, ros_msg.pose_trajectory_in_task) - ros_msg.pose_trajectory_in_task_is_set = proto.HasField("pose_trajectory_in_task") - ros_msg.maximum_acceleration = proto.maximum_acceleration.value - ros_msg.maximum_acceleration_is_set = proto.HasField("maximum_acceleration") - ros_msg.max_linear_velocity = proto.max_linear_velocity.value - ros_msg.max_linear_velocity_is_set = proto.HasField("max_linear_velocity") - ros_msg.max_angular_velocity = proto.max_angular_velocity.value - ros_msg.max_angular_velocity_is_set = proto.HasField("max_angular_velocity") - ros_msg.max_pos_tracking_error = proto.max_pos_tracking_error.value - ros_msg.max_pos_tracking_error_is_set = proto.HasField("max_pos_tracking_error") - ros_msg.max_rot_tracking_error = proto.max_rot_tracking_error.value - ros_msg.max_rot_tracking_error_is_set = proto.HasField("max_rot_tracking_error") - convert_proto_to_bosdyn_msgs_arm_surface_contact_request_one_of_joint_configuration(proto, ros_msg.joint_configuration) - ros_msg.x_axis.value = proto.x_axis - ros_msg.y_axis.value = proto.y_axis - ros_msg.z_axis.value = proto.z_axis - convert_proto_to_geometry_msgs_vector3(proto.press_force_percentage, ros_msg.press_force_percentage) - ros_msg.press_force_percentage_is_set = proto.HasField("press_force_percentage") - ros_msg.xy_admittance.value = proto.xy_admittance - ros_msg.z_admittance.value = proto.z_admittance - ros_msg.xy_to_z_cross_term_admittance.value = proto.xy_to_z_cross_term_admittance - convert_proto_to_geometry_msgs_vector3(proto.bias_force_ewrt_body, ros_msg.bias_force_ewrt_body) - ros_msg.bias_force_ewrt_body_is_set = proto.HasField("bias_force_ewrt_body") - convert_proto_to_bosdyn_msgs_claw_gripper_command_request(proto.gripper_command, ros_msg.gripper_command) - ros_msg.gripper_command_is_set = proto.HasField("gripper_command") - ros_msg.is_robot_following_hand = proto.is_robot_following_hand - - -def convert_bosdyn_msgs_arm_surface_contact_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactRequest", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Request") -> None: - proto.Clear() - proto.root_frame_name = ros_msg.root_frame_name - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - if ros_msg.root_tform_task_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.root_tform_task, proto.root_tform_task) - if ros_msg.pose_trajectory_in_task_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.pose_trajectory_in_task, proto.pose_trajectory_in_task) - if ros_msg.maximum_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_acceleration, proto.maximum_acceleration) - if ros_msg.max_linear_velocity_is_set: - convert_float64_to_proto(ros_msg.max_linear_velocity, proto.max_linear_velocity) - if ros_msg.max_angular_velocity_is_set: - convert_float64_to_proto(ros_msg.max_angular_velocity, proto.max_angular_velocity) - if ros_msg.max_pos_tracking_error_is_set: - convert_float64_to_proto(ros_msg.max_pos_tracking_error, proto.max_pos_tracking_error) - if ros_msg.max_rot_tracking_error_is_set: - convert_float64_to_proto(ros_msg.max_rot_tracking_error, proto.max_rot_tracking_error) - convert_bosdyn_msgs_arm_surface_contact_request_one_of_joint_configuration_to_proto(ros_msg.joint_configuration, proto) - proto.x_axis = ros_msg.x_axis.value - proto.y_axis = ros_msg.y_axis.value - proto.z_axis = ros_msg.z_axis.value - if ros_msg.press_force_percentage_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.press_force_percentage, proto.press_force_percentage) - proto.xy_admittance = ros_msg.xy_admittance.value - proto.z_admittance = ros_msg.z_admittance.value - proto.xy_to_z_cross_term_admittance = ros_msg.xy_to_z_cross_term_admittance.value - if ros_msg.bias_force_ewrt_body_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.bias_force_ewrt_body, proto.bias_force_ewrt_body) - if ros_msg.gripper_command_is_set: - convert_bosdyn_msgs_claw_gripper_command_request_to_proto(ros_msg.gripper_command, proto.gripper_command) - proto.is_robot_following_hand = ros_msg.is_robot_following_hand - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_feedback(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactFeedback") -> None: - pass - - -def convert_bosdyn_msgs_arm_surface_contact_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactFeedback", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact(proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContact") -> None: - pass - - -def convert_bosdyn_msgs_arm_surface_contact_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContact", proto: "bosdyn.api.arm_surface_contact_pb2.ArmSurfaceContact") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_command(proto: "bosdyn.api.arm_surface_contact_service_pb2.ArmSurfaceContactCommand", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactCommand") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_arm_surface_contact_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - - -def convert_bosdyn_msgs_arm_surface_contact_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactCommand", proto: "bosdyn.api.arm_surface_contact_service_pb2.ArmSurfaceContactCommand") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.request_is_set: - convert_bosdyn_msgs_arm_surface_contact_request_to_proto(ros_msg.request, proto.request) - - -def convert_proto_to_bosdyn_msgs_arm_surface_contact_response(proto: "bosdyn.api.arm_surface_contact_service_pb2.ArmSurfaceContactResponse", ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_arm_surface_contact_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmSurfaceContactResponse", proto: "bosdyn.api.arm_surface_contact_service_pb2.ArmSurfaceContactResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_auth_token_request(proto: "bosdyn.api.auth_pb2.GetAuthTokenRequest", ros_msg: "bosdyn_msgs.msgs.GetAuthTokenRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.username = proto.username - ros_msg.password = proto.password - ros_msg.token = proto.token - - -def convert_bosdyn_msgs_get_auth_token_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAuthTokenRequest", proto: "bosdyn.api.auth_pb2.GetAuthTokenRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.username = ros_msg.username - proto.password = ros_msg.password - proto.token = ros_msg.token - - -def convert_proto_to_bosdyn_msgs_get_auth_token_response_status(proto: "bosdyn.api.auth_pb2.GetAuthTokenResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetAuthTokenResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_auth_token_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAuthTokenResponseStatus", proto: "bosdyn.api.auth_pb2.GetAuthTokenResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_auth_token_response(proto: "bosdyn.api.auth_pb2.GetAuthTokenResponse", ros_msg: "bosdyn_msgs.msgs.GetAuthTokenResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.token = proto.token - - -def convert_bosdyn_msgs_get_auth_token_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAuthTokenResponse", proto: "bosdyn.api.auth_pb2.GetAuthTokenResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.token = ros_msg.token - - -def convert_proto_to_bosdyn_msgs_params(proto: "bosdyn.api.auto_return.auto_return_pb2.Params", ros_msg: "bosdyn_msgs.msgs.Params") -> None: - ros_msg.max_displacement = proto.max_displacement - convert_proto_to_builtin_interfaces_duration(proto.max_duration, ros_msg.max_duration) - ros_msg.max_duration_is_set = proto.HasField("max_duration") - - -def convert_bosdyn_msgs_params_to_proto(ros_msg: "bosdyn_msgs.msgs.Params", proto: "bosdyn.api.auto_return.auto_return_pb2.Params") -> None: - proto.Clear() - proto.max_displacement = ros_msg.max_displacement - if ros_msg.max_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.max_duration, proto.max_duration) - - -def convert_proto_to_bosdyn_msgs_configure_request(proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureRequest", ros_msg: "bosdyn_msgs.msgs.ConfigureRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - ros_msg.clear_buffer = proto.clear_buffer - - -def convert_bosdyn_msgs_configure_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ConfigureRequest", proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.params_is_set: - convert_bosdyn_msgs_params_to_proto(ros_msg.params, proto.params) - proto.clear_buffer = ros_msg.clear_buffer - - -def convert_proto_to_bosdyn_msgs_configure_response_status(proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureResponse.Status", ros_msg: "bosdyn_msgs.msgs.ConfigureResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_configure_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ConfigureResponseStatus", proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_configure_response(proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureResponse", ros_msg: "bosdyn_msgs.msgs.ConfigureResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_params(proto.invalid_params, ros_msg.invalid_params) - ros_msg.invalid_params_is_set = proto.HasField("invalid_params") - - -def convert_bosdyn_msgs_configure_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ConfigureResponse", proto: "bosdyn.api.auto_return.auto_return_pb2.ConfigureResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.invalid_params_is_set: - convert_bosdyn_msgs_params_to_proto(ros_msg.invalid_params, proto.invalid_params) - - -def convert_proto_to_bosdyn_msgs_get_configuration_request(proto: "bosdyn.api.auto_return.auto_return_pb2.GetConfigurationRequest", ros_msg: "bosdyn_msgs.msgs.GetConfigurationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_configuration_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetConfigurationRequest", proto: "bosdyn.api.auto_return.auto_return_pb2.GetConfigurationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_configuration_response(proto: "bosdyn.api.auto_return.auto_return_pb2.GetConfigurationResponse", ros_msg: "bosdyn_msgs.msgs.GetConfigurationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.enabled = proto.enabled - convert_proto_to_bosdyn_msgs_configure_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - - -def convert_bosdyn_msgs_get_configuration_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetConfigurationResponse", proto: "bosdyn.api.auto_return.auto_return_pb2.GetConfigurationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.enabled = ros_msg.enabled - if ros_msg.request_is_set: - convert_bosdyn_msgs_configure_request_to_proto(ros_msg.request, proto.request) - - -def convert_proto_to_bosdyn_msgs_start_request(proto: "bosdyn.api.auto_return.auto_return_pb2.StartRequest", ros_msg: "bosdyn_msgs.msgs.StartRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_start_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRequest", proto: "bosdyn.api.auto_return.auto_return_pb2.StartRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.params_is_set: - convert_bosdyn_msgs_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_start_response_status(proto: "bosdyn.api.auto_return.auto_return_pb2.StartResponse.Status", ros_msg: "bosdyn_msgs.msgs.StartResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_start_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StartResponseStatus", proto: "bosdyn.api.auto_return.auto_return_pb2.StartResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_start_response(proto: "bosdyn.api.auto_return.auto_return_pb2.StartResponse", ros_msg: "bosdyn_msgs.msgs.StartResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_params(proto.invalid_params, ros_msg.invalid_params) - ros_msg.invalid_params_is_set = proto.HasField("invalid_params") - - -def convert_bosdyn_msgs_start_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StartResponse", proto: "bosdyn.api.auto_return.auto_return_pb2.StartResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.invalid_params_is_set: - convert_bosdyn_msgs_params_to_proto(ros_msg.invalid_params, proto.invalid_params) - - -def convert_proto_to_bosdyn_msgs_failed_element(proto: "bosdyn.api.autowalk.autowalk_pb2.FailedElement", ros_msg: "bosdyn_msgs.msgs.FailedElement") -> None: - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(_item) - ros_msg.warnings = [] - for _item in proto.warnings: - ros_msg.warnings.append(_item) - - -def convert_bosdyn_msgs_failed_element_to_proto(ros_msg: "bosdyn_msgs.msgs.FailedElement", proto: "bosdyn.api.autowalk.autowalk_pb2.FailedElement") -> None: - proto.Clear() - del proto.errors[:] - for _item in ros_msg.errors: - proto.errors.append(_item) - del proto.warnings[:] - for _item in ros_msg.warnings: - proto.warnings.append(_item) - - -def convert_proto_to_bosdyn_msgs_node_identifier(proto: "bosdyn.api.autowalk.autowalk_pb2.NodeIdentifier", ros_msg: "bosdyn_msgs.msgs.NodeIdentifier") -> None: - ros_msg.node_id = proto.node_id - ros_msg.user_data_id = proto.user_data_id - - -def convert_bosdyn_msgs_node_identifier_to_proto(ros_msg: "bosdyn_msgs.msgs.NodeIdentifier", proto: "bosdyn.api.autowalk.autowalk_pb2.NodeIdentifier") -> None: - proto.Clear() - proto.node_id = ros_msg.node_id - proto.user_data_id = ros_msg.user_data_id - - -def convert_proto_to_bosdyn_msgs_element_identifiers(proto: "bosdyn.api.autowalk.autowalk_pb2.ElementIdentifiers", ros_msg: "bosdyn_msgs.msgs.ElementIdentifiers") -> None: - convert_proto_to_bosdyn_msgs_node_identifier(proto.root_id, ros_msg.root_id) - ros_msg.root_id_is_set = proto.HasField("root_id") - convert_proto_to_bosdyn_msgs_node_identifier(proto.action_id, ros_msg.action_id) - ros_msg.action_id_is_set = proto.HasField("action_id") - - -def convert_bosdyn_msgs_element_identifiers_to_proto(ros_msg: "bosdyn_msgs.msgs.ElementIdentifiers", proto: "bosdyn.api.autowalk.autowalk_pb2.ElementIdentifiers") -> None: - proto.Clear() - if ros_msg.root_id_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.root_id, proto.root_id) - if ros_msg.action_id_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.action_id, proto.action_id) - - -def convert_proto_to_bosdyn_msgs_compile_autowalk_request(proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkRequest", ros_msg: "bosdyn_msgs.msgs.CompileAutowalkRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_walk(proto.walk, ros_msg.walk) - ros_msg.walk_is_set = proto.HasField("walk") - ros_msg.treat_warnings_as_errors = proto.treat_warnings_as_errors - - -def convert_bosdyn_msgs_compile_autowalk_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CompileAutowalkRequest", proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.walk_is_set: - convert_bosdyn_msgs_walk_to_proto(ros_msg.walk, proto.walk) - proto.treat_warnings_as_errors = ros_msg.treat_warnings_as_errors - - -def convert_proto_to_bosdyn_msgs_compile_autowalk_response_status(proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkResponse.Status", ros_msg: "bosdyn_msgs.msgs.CompileAutowalkResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_compile_autowalk_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CompileAutowalkResponseStatus", proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_compile_autowalk_response(proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkResponse", ros_msg: "bosdyn_msgs.msgs.CompileAutowalkResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_node(proto.root, ros_msg.root) - ros_msg.root_is_set = proto.HasField("root") - from bosdyn_msgs.msg import ElementIdentifiers - ros_msg.element_identifiers = [] - for _item in proto.element_identifiers: - ros_msg.element_identifiers.append(ElementIdentifiers()) - convert_proto_to_bosdyn_msgs_element_identifiers(_item, ros_msg.element_identifiers[-1]) - from bosdyn_msgs.msg import KeyInt32ValueBosdynMsgsFailedElement - ros_msg.failed_elements = [] - for _item in proto.failed_elements: - ros_msg.failed_elements.append(KeyInt32ValueBosdynMsgsFailedElement()) - ros_msg.failed_elements[-1].key = _item - convert_proto_to_bosdyn_msgs_failed_element(proto.failed_elements[_item], ros_msg.failed_elements[-1].value) - convert_proto_to_bosdyn_msgs_node_identifier(proto.docking_node, ros_msg.docking_node) - ros_msg.docking_node_is_set = proto.HasField("docking_node") - convert_proto_to_bosdyn_msgs_node_identifier(proto.loop_node, ros_msg.loop_node) - ros_msg.loop_node_is_set = proto.HasField("loop_node") - - -def convert_bosdyn_msgs_compile_autowalk_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CompileAutowalkResponse", proto: "bosdyn.api.autowalk.autowalk_pb2.CompileAutowalkResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.root_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.root, proto.root) - del proto.element_identifiers[:] - for _item in ros_msg.element_identifiers: - convert_bosdyn_msgs_element_identifiers_to_proto(_item, proto.element_identifiers.add()) - for _item in ros_msg.failed_elements: - convert_bosdyn_msgs_failed_element_to_proto(_item.value, proto.failed_elements[_item.key]) - if ros_msg.docking_node_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.docking_node, proto.docking_node) - if ros_msg.loop_node_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.loop_node, proto.loop_node) - - -def convert_proto_to_bosdyn_msgs_load_autowalk_request(proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkRequest", ros_msg: "bosdyn_msgs.msgs.LoadAutowalkRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_walk(proto.walk, ros_msg.walk) - ros_msg.walk_is_set = proto.HasField("walk") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - ros_msg.treat_warnings_as_errors = proto.treat_warnings_as_errors - - -def convert_bosdyn_msgs_load_autowalk_request_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadAutowalkRequest", proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.walk_is_set: - convert_bosdyn_msgs_walk_to_proto(ros_msg.walk, proto.walk) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - proto.treat_warnings_as_errors = ros_msg.treat_warnings_as_errors - - -def convert_proto_to_bosdyn_msgs_load_autowalk_response_status(proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkResponse.Status", ros_msg: "bosdyn_msgs.msgs.LoadAutowalkResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_load_autowalk_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadAutowalkResponseStatus", proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_load_autowalk_response(proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkResponse", ros_msg: "bosdyn_msgs.msgs.LoadAutowalkResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - from bosdyn_msgs.msg import FailedNode - ros_msg.failed_nodes = [] - for _item in proto.failed_nodes: - ros_msg.failed_nodes.append(FailedNode()) - convert_proto_to_bosdyn_msgs_failed_node(_item, ros_msg.failed_nodes[-1]) - from bosdyn_msgs.msg import ElementIdentifiers - ros_msg.element_identifiers = [] - for _item in proto.element_identifiers: - ros_msg.element_identifiers.append(ElementIdentifiers()) - convert_proto_to_bosdyn_msgs_element_identifiers(_item, ros_msg.element_identifiers[-1]) - from bosdyn_msgs.msg import KeyInt32ValueBosdynMsgsFailedElement - ros_msg.failed_elements = [] - for _item in proto.failed_elements: - ros_msg.failed_elements.append(KeyInt32ValueBosdynMsgsFailedElement()) - ros_msg.failed_elements[-1].key = _item - convert_proto_to_bosdyn_msgs_failed_element(proto.failed_elements[_item], ros_msg.failed_elements[-1].value) - ros_msg.mission_id = proto.mission_id - convert_proto_to_bosdyn_msgs_node_identifier(proto.docking_node, ros_msg.docking_node) - ros_msg.docking_node_is_set = proto.HasField("docking_node") - convert_proto_to_bosdyn_msgs_node_identifier(proto.loop_node, ros_msg.loop_node) - ros_msg.loop_node_is_set = proto.HasField("loop_node") - - -def convert_bosdyn_msgs_load_autowalk_response_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadAutowalkResponse", proto: "bosdyn.api.autowalk.autowalk_pb2.LoadAutowalkResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - del proto.failed_nodes[:] - for _item in ros_msg.failed_nodes: - convert_bosdyn_msgs_failed_node_to_proto(_item, proto.failed_nodes.add()) - del proto.element_identifiers[:] - for _item in ros_msg.element_identifiers: - convert_bosdyn_msgs_element_identifiers_to_proto(_item, proto.element_identifiers.add()) - for _item in ros_msg.failed_elements: - convert_bosdyn_msgs_failed_element_to_proto(_item.value, proto.failed_elements[_item.key]) - proto.mission_id = ros_msg.mission_id - if ros_msg.docking_node_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.docking_node, proto.docking_node) - if ros_msg.loop_node_is_set: - convert_bosdyn_msgs_node_identifier_to_proto(ros_msg.loop_node, proto.loop_node) - - -def convert_proto_to_bosdyn_msgs_walk(proto: "bosdyn.api.autowalk.walks_pb2.Walk", ros_msg: "bosdyn_msgs.msgs.Walk") -> None: - convert_proto_to_bosdyn_msgs_global_parameters(proto.global_parameters, ros_msg.global_parameters) - ros_msg.global_parameters_is_set = proto.HasField("global_parameters") - convert_proto_to_bosdyn_msgs_playback_mode(proto.playback_mode, ros_msg.playback_mode) - ros_msg.playback_mode_is_set = proto.HasField("playback_mode") - ros_msg.map_name = proto.map_name - ros_msg.mission_name = proto.mission_name - from bosdyn_msgs.msg import Element - ros_msg.elements = [] - for _item in proto.elements: - ros_msg.elements.append(Element()) - convert_proto_to_bosdyn_msgs_element(_item, ros_msg.elements[-1]) - from bosdyn_msgs.msg import Dock - ros_msg.docks = [] - for _item in proto.docks: - ros_msg.docks.append(Dock()) - convert_proto_to_bosdyn_msgs_dock(_item, ros_msg.docks[-1]) - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_walk_to_proto(ros_msg: "bosdyn_msgs.msgs.Walk", proto: "bosdyn.api.autowalk.walks_pb2.Walk") -> None: - proto.Clear() - if ros_msg.global_parameters_is_set: - convert_bosdyn_msgs_global_parameters_to_proto(ros_msg.global_parameters, proto.global_parameters) - if ros_msg.playback_mode_is_set: - convert_bosdyn_msgs_playback_mode_to_proto(ros_msg.playback_mode, proto.playback_mode) - proto.map_name = ros_msg.map_name - proto.mission_name = ros_msg.mission_name - del proto.elements[:] - for _item in ros_msg.elements: - convert_bosdyn_msgs_element_to_proto(_item, proto.elements.add()) - del proto.docks[:] - for _item in ros_msg.docks: - convert_bosdyn_msgs_dock_to_proto(_item, proto.docks.add()) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_global_parameters(proto: "bosdyn.api.autowalk.walks_pb2.GlobalParameters", ros_msg: "bosdyn_msgs.msgs.GlobalParameters") -> None: - ros_msg.group_name = proto.group_name - ros_msg.should_autofocus_ptz = proto.should_autofocus_ptz - ros_msg.self_right_attempts = proto.self_right_attempts - from bosdyn_msgs.msg import ActionRemoteGrpc - ros_msg.post_mission_callbacks = [] - for _item in proto.post_mission_callbacks: - ros_msg.post_mission_callbacks.append(ActionRemoteGrpc()) - convert_proto_to_bosdyn_msgs_action_remote_grpc(_item, ros_msg.post_mission_callbacks[-1]) - ros_msg.skip_actions = proto.skip_actions - - -def convert_bosdyn_msgs_global_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.GlobalParameters", proto: "bosdyn.api.autowalk.walks_pb2.GlobalParameters") -> None: - proto.Clear() - proto.group_name = ros_msg.group_name - proto.should_autofocus_ptz = ros_msg.should_autofocus_ptz - proto.self_right_attempts = ros_msg.self_right_attempts - del proto.post_mission_callbacks[:] - for _item in ros_msg.post_mission_callbacks: - convert_bosdyn_msgs_action_remote_grpc_to_proto(_item, proto.post_mission_callbacks.add()) - proto.skip_actions = ros_msg.skip_actions - - -def convert_proto_to_bosdyn_msgs_dock(proto: "bosdyn.api.autowalk.walks_pb2.Dock", ros_msg: "bosdyn_msgs.msgs.Dock") -> None: - ros_msg.dock_id = proto.dock_id - ros_msg.docked_waypoint_id = proto.docked_waypoint_id - convert_proto_to_bosdyn_msgs_target(proto.target_prep_pose, ros_msg.target_prep_pose) - ros_msg.target_prep_pose_is_set = proto.HasField("target_prep_pose") - convert_proto_to_builtin_interfaces_duration(proto.prompt_duration, ros_msg.prompt_duration) - ros_msg.prompt_duration_is_set = proto.HasField("prompt_duration") - - -def convert_bosdyn_msgs_dock_to_proto(ros_msg: "bosdyn_msgs.msgs.Dock", proto: "bosdyn.api.autowalk.walks_pb2.Dock") -> None: - proto.Clear() - proto.dock_id = ros_msg.dock_id - proto.docked_waypoint_id = ros_msg.docked_waypoint_id - if ros_msg.target_prep_pose_is_set: - convert_bosdyn_msgs_target_to_proto(ros_msg.target_prep_pose, proto.target_prep_pose) - if ros_msg.prompt_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.prompt_duration, proto.prompt_duration) - - -def convert_proto_to_bosdyn_msgs_playback_mode_once(proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Once", ros_msg: "bosdyn_msgs.msgs.PlaybackModeOnce") -> None: - ros_msg.skip_docking_after_completion = proto.skip_docking_after_completion - - -def convert_bosdyn_msgs_playback_mode_once_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaybackModeOnce", proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Once") -> None: - proto.Clear() - proto.skip_docking_after_completion = ros_msg.skip_docking_after_completion - - -def convert_proto_to_bosdyn_msgs_playback_mode_periodic(proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Periodic", ros_msg: "bosdyn_msgs.msgs.PlaybackModePeriodic") -> None: - convert_proto_to_builtin_interfaces_duration(proto.interval, ros_msg.interval) - ros_msg.interval_is_set = proto.HasField("interval") - ros_msg.repetitions = proto.repetitions - - -def convert_bosdyn_msgs_playback_mode_periodic_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaybackModePeriodic", proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Periodic") -> None: - proto.Clear() - if ros_msg.interval_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.interval, proto.interval) - proto.repetitions = ros_msg.repetitions - - -def convert_proto_to_bosdyn_msgs_playback_mode_continuous(proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Continuous", ros_msg: "bosdyn_msgs.msgs.PlaybackModeContinuous") -> None: - pass - - -def convert_bosdyn_msgs_playback_mode_continuous_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaybackModeContinuous", proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode.Continuous") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_playback_mode_one_of_mode(proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode", ros_msg: "bosdyn_msgs.msgs.PlaybackModeOneOfMode") -> None: - if proto.HasField("once"): - ros_msg.mode_choice = ros_msg.MODE_ONCE_SET - convert_proto_to_bosdyn_msgs_playback_mode_once(proto.once, ros_msg.once) - if proto.HasField("periodic"): - ros_msg.mode_choice = ros_msg.MODE_PERIODIC_SET - convert_proto_to_bosdyn_msgs_playback_mode_periodic(proto.periodic, ros_msg.periodic) - if proto.HasField("continuous"): - ros_msg.mode_choice = ros_msg.MODE_CONTINUOUS_SET - convert_proto_to_bosdyn_msgs_playback_mode_continuous(proto.continuous, ros_msg.continuous) - - -def convert_bosdyn_msgs_playback_mode_one_of_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaybackModeOneOfMode", proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode") -> None: - proto.ClearField("mode") - if ros_msg.mode_choice == ros_msg.MODE_ONCE_SET: - convert_bosdyn_msgs_playback_mode_once_to_proto(ros_msg.once, proto.once) - if ros_msg.mode_choice == ros_msg.MODE_PERIODIC_SET: - convert_bosdyn_msgs_playback_mode_periodic_to_proto(ros_msg.periodic, proto.periodic) - if ros_msg.mode_choice == ros_msg.MODE_CONTINUOUS_SET: - convert_bosdyn_msgs_playback_mode_continuous_to_proto(ros_msg.continuous, proto.continuous) - - -def convert_proto_to_bosdyn_msgs_playback_mode(proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode", ros_msg: "bosdyn_msgs.msgs.PlaybackMode") -> None: - convert_proto_to_bosdyn_msgs_playback_mode_one_of_mode(proto, ros_msg.mode) - - -def convert_bosdyn_msgs_playback_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaybackMode", proto: "bosdyn.api.autowalk.walks_pb2.PlaybackMode") -> None: - proto.Clear() - convert_bosdyn_msgs_playback_mode_one_of_mode_to_proto(ros_msg.mode, proto) - - -def convert_proto_to_bosdyn_msgs_element(proto: "bosdyn.api.autowalk.walks_pb2.Element", ros_msg: "bosdyn_msgs.msgs.Element") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_target(proto.target, ros_msg.target) - ros_msg.target_is_set = proto.HasField("target") - convert_proto_to_bosdyn_msgs_failure_behavior(proto.target_failure_behavior, ros_msg.target_failure_behavior) - ros_msg.target_failure_behavior_is_set = proto.HasField("target_failure_behavior") - convert_proto_to_bosdyn_msgs_action(proto.action, ros_msg.action) - ros_msg.action_is_set = proto.HasField("action") - convert_proto_to_bosdyn_msgs_action_wrapper(proto.action_wrapper, ros_msg.action_wrapper) - ros_msg.action_wrapper_is_set = proto.HasField("action_wrapper") - convert_proto_to_bosdyn_msgs_failure_behavior(proto.action_failure_behavior, ros_msg.action_failure_behavior) - ros_msg.action_failure_behavior_is_set = proto.HasField("action_failure_behavior") - ros_msg.is_skipped = proto.is_skipped - convert_proto_to_bosdyn_msgs_battery_monitor(proto.battery_monitor, ros_msg.battery_monitor) - ros_msg.battery_monitor_is_set = proto.HasField("battery_monitor") - convert_proto_to_builtin_interfaces_duration(proto.action_duration, ros_msg.action_duration) - ros_msg.action_duration_is_set = proto.HasField("action_duration") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_element_to_proto(ros_msg: "bosdyn_msgs.msgs.Element", proto: "bosdyn.api.autowalk.walks_pb2.Element") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.target_is_set: - convert_bosdyn_msgs_target_to_proto(ros_msg.target, proto.target) - if ros_msg.target_failure_behavior_is_set: - convert_bosdyn_msgs_failure_behavior_to_proto(ros_msg.target_failure_behavior, proto.target_failure_behavior) - if ros_msg.action_is_set: - convert_bosdyn_msgs_action_to_proto(ros_msg.action, proto.action) - if ros_msg.action_wrapper_is_set: - convert_bosdyn_msgs_action_wrapper_to_proto(ros_msg.action_wrapper, proto.action_wrapper) - if ros_msg.action_failure_behavior_is_set: - convert_bosdyn_msgs_failure_behavior_to_proto(ros_msg.action_failure_behavior, proto.action_failure_behavior) - proto.is_skipped = ros_msg.is_skipped - if ros_msg.battery_monitor_is_set: - convert_bosdyn_msgs_battery_monitor_to_proto(ros_msg.battery_monitor, proto.battery_monitor) - if ros_msg.action_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.action_duration, proto.action_duration) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_target_relocalize(proto: "bosdyn.api.autowalk.walks_pb2.Target.Relocalize", ros_msg: "bosdyn_msgs.msgs.TargetRelocalize") -> None: - convert_proto_to_bosdyn_msgs_set_localization_request(proto.set_localization_request, ros_msg.set_localization_request) - ros_msg.set_localization_request_is_set = proto.HasField("set_localization_request") - - -def convert_bosdyn_msgs_target_relocalize_to_proto(ros_msg: "bosdyn_msgs.msgs.TargetRelocalize", proto: "bosdyn.api.autowalk.walks_pb2.Target.Relocalize") -> None: - proto.Clear() - if ros_msg.set_localization_request_is_set: - convert_bosdyn_msgs_set_localization_request_to_proto(ros_msg.set_localization_request, proto.set_localization_request) - - -def convert_proto_to_bosdyn_msgs_target_navigate_to(proto: "bosdyn.api.autowalk.walks_pb2.Target.NavigateTo", ros_msg: "bosdyn_msgs.msgs.TargetNavigateTo") -> None: - ros_msg.destination_waypoint_id = proto.destination_waypoint_id - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - - -def convert_bosdyn_msgs_target_navigate_to_to_proto(ros_msg: "bosdyn_msgs.msgs.TargetNavigateTo", proto: "bosdyn.api.autowalk.walks_pb2.Target.NavigateTo") -> None: - proto.Clear() - proto.destination_waypoint_id = ros_msg.destination_waypoint_id - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - - -def convert_proto_to_bosdyn_msgs_target_navigate_route(proto: "bosdyn.api.autowalk.walks_pb2.Target.NavigateRoute", ros_msg: "bosdyn_msgs.msgs.TargetNavigateRoute") -> None: - convert_proto_to_bosdyn_msgs_route(proto.route, ros_msg.route) - ros_msg.route_is_set = proto.HasField("route") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - - -def convert_bosdyn_msgs_target_navigate_route_to_proto(ros_msg: "bosdyn_msgs.msgs.TargetNavigateRoute", proto: "bosdyn.api.autowalk.walks_pb2.Target.NavigateRoute") -> None: - proto.Clear() - if ros_msg.route_is_set: - convert_bosdyn_msgs_route_to_proto(ros_msg.route, proto.route) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - - -def convert_proto_to_bosdyn_msgs_target_one_of_target(proto: "bosdyn.api.autowalk.walks_pb2.Target", ros_msg: "bosdyn_msgs.msgs.TargetOneOfTarget") -> None: - if proto.HasField("navigate_to"): - ros_msg.target_choice = ros_msg.TARGET_NAVIGATE_TO_SET - convert_proto_to_bosdyn_msgs_target_navigate_to(proto.navigate_to, ros_msg.navigate_to) - if proto.HasField("navigate_route"): - ros_msg.target_choice = ros_msg.TARGET_NAVIGATE_ROUTE_SET - convert_proto_to_bosdyn_msgs_target_navigate_route(proto.navigate_route, ros_msg.navigate_route) - - -def convert_bosdyn_msgs_target_one_of_target_to_proto(ros_msg: "bosdyn_msgs.msgs.TargetOneOfTarget", proto: "bosdyn.api.autowalk.walks_pb2.Target") -> None: - proto.ClearField("target") - if ros_msg.target_choice == ros_msg.TARGET_NAVIGATE_TO_SET: - convert_bosdyn_msgs_target_navigate_to_to_proto(ros_msg.navigate_to, proto.navigate_to) - if ros_msg.target_choice == ros_msg.TARGET_NAVIGATE_ROUTE_SET: - convert_bosdyn_msgs_target_navigate_route_to_proto(ros_msg.navigate_route, proto.navigate_route) - - -def convert_proto_to_bosdyn_msgs_target(proto: "bosdyn.api.autowalk.walks_pb2.Target", ros_msg: "bosdyn_msgs.msgs.Target") -> None: - convert_proto_to_bosdyn_msgs_target_one_of_target(proto, ros_msg.target) - convert_proto_to_bosdyn_msgs_target_relocalize(proto.relocalize, ros_msg.relocalize) - ros_msg.relocalize_is_set = proto.HasField("relocalize") - - -def convert_bosdyn_msgs_target_to_proto(ros_msg: "bosdyn_msgs.msgs.Target", proto: "bosdyn.api.autowalk.walks_pb2.Target") -> None: - proto.Clear() - convert_bosdyn_msgs_target_one_of_target_to_proto(ros_msg.target, proto) - if ros_msg.relocalize_is_set: - convert_bosdyn_msgs_target_relocalize_to_proto(ros_msg.relocalize, proto.relocalize) - - -def convert_proto_to_bosdyn_msgs_action_sleep(proto: "bosdyn.api.autowalk.walks_pb2.Action.Sleep", ros_msg: "bosdyn_msgs.msgs.ActionSleep") -> None: - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - ros_msg.duration_is_set = proto.HasField("duration") - - -def convert_bosdyn_msgs_action_sleep_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionSleep", proto: "bosdyn.api.autowalk.walks_pb2.Action.Sleep") -> None: - proto.Clear() - if ros_msg.duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - - -def convert_proto_to_bosdyn_msgs_action_data_acquisition(proto: "bosdyn.api.autowalk.walks_pb2.Action.DataAcquisition", ros_msg: "bosdyn_msgs.msgs.ActionDataAcquisition") -> None: - convert_proto_to_bosdyn_msgs_acquire_data_request(proto.acquire_data_request, ros_msg.acquire_data_request) - ros_msg.acquire_data_request_is_set = proto.HasField("acquire_data_request") - ros_msg.completion_behavior.value = proto.completion_behavior - convert_proto_to_bosdyn_msgs_acquisition_capability_list(proto.last_known_capabilities, ros_msg.last_known_capabilities) - ros_msg.last_known_capabilities_is_set = proto.HasField("last_known_capabilities") - from bosdyn_msgs.msg import ImageCaptureAndSource - ros_msg.record_time_images = [] - for _item in proto.record_time_images: - ros_msg.record_time_images.append(ImageCaptureAndSource()) - convert_proto_to_bosdyn_msgs_image_capture_and_source(_item, ros_msg.record_time_images[-1]) - - -def convert_bosdyn_msgs_action_data_acquisition_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionDataAcquisition", proto: "bosdyn.api.autowalk.walks_pb2.Action.DataAcquisition") -> None: - proto.Clear() - if ros_msg.acquire_data_request_is_set: - convert_bosdyn_msgs_acquire_data_request_to_proto(ros_msg.acquire_data_request, proto.acquire_data_request) - proto.completion_behavior = ros_msg.completion_behavior.value - if ros_msg.last_known_capabilities_is_set: - convert_bosdyn_msgs_acquisition_capability_list_to_proto(ros_msg.last_known_capabilities, proto.last_known_capabilities) - del proto.record_time_images[:] - for _item in ros_msg.record_time_images: - convert_bosdyn_msgs_image_capture_and_source_to_proto(_item, proto.record_time_images.add()) - - -def convert_proto_to_bosdyn_msgs_action_remote_grpc(proto: "bosdyn.api.autowalk.walks_pb2.Action.RemoteGrpc", ros_msg: "bosdyn_msgs.msgs.ActionRemoteGrpc") -> None: - ros_msg.service_name = proto.service_name - convert_proto_to_builtin_interfaces_duration(proto.rpc_timeout, ros_msg.rpc_timeout) - ros_msg.rpc_timeout_is_set = proto.HasField("rpc_timeout") - ros_msg.lease_resources = [] - for _item in proto.lease_resources: - ros_msg.lease_resources.append(_item) - convert_proto_to_bosdyn_msgs_custom_param_collection(proto.parameters, ros_msg.parameters) - ros_msg.parameters_is_set = proto.HasField("parameters") - from bosdyn_msgs.msg import ImageCaptureAndSource - ros_msg.record_time_images = [] - for _item in proto.record_time_images: - ros_msg.record_time_images.append(ImageCaptureAndSource()) - convert_proto_to_bosdyn_msgs_image_capture_and_source(_item, ros_msg.record_time_images[-1]) - - -def convert_bosdyn_msgs_action_remote_grpc_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionRemoteGrpc", proto: "bosdyn.api.autowalk.walks_pb2.Action.RemoteGrpc") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - if ros_msg.rpc_timeout_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.rpc_timeout, proto.rpc_timeout) - del proto.lease_resources[:] - for _item in ros_msg.lease_resources: - proto.lease_resources.append(_item) - if ros_msg.parameters_is_set: - convert_bosdyn_msgs_custom_param_collection_to_proto(ros_msg.parameters, proto.parameters) - del proto.record_time_images[:] - for _item in ros_msg.record_time_images: - convert_bosdyn_msgs_image_capture_and_source_to_proto(_item, proto.record_time_images.add()) - - -def convert_proto_to_bosdyn_msgs_action_one_of_action(proto: "bosdyn.api.autowalk.walks_pb2.Action", ros_msg: "bosdyn_msgs.msgs.ActionOneOfAction") -> None: - if proto.HasField("sleep"): - ros_msg.action_choice = ros_msg.ACTION_SLEEP_SET - convert_proto_to_bosdyn_msgs_action_sleep(proto.sleep, ros_msg.sleep) - if proto.HasField("data_acquisition"): - ros_msg.action_choice = ros_msg.ACTION_DATA_ACQUISITION_SET - convert_proto_to_bosdyn_msgs_action_data_acquisition(proto.data_acquisition, ros_msg.data_acquisition) - if proto.HasField("remote_grpc"): - ros_msg.action_choice = ros_msg.ACTION_REMOTE_GRPC_SET - convert_proto_to_bosdyn_msgs_action_remote_grpc(proto.remote_grpc, ros_msg.remote_grpc) - if proto.HasField("node"): - ros_msg.action_choice = ros_msg.ACTION_NODE_SET - convert_proto_to_bosdyn_msgs_node(proto.node, ros_msg.node) - - -def convert_bosdyn_msgs_action_one_of_action_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionOneOfAction", proto: "bosdyn.api.autowalk.walks_pb2.Action") -> None: - proto.ClearField("action") - if ros_msg.action_choice == ros_msg.ACTION_SLEEP_SET: - convert_bosdyn_msgs_action_sleep_to_proto(ros_msg.sleep, proto.sleep) - if ros_msg.action_choice == ros_msg.ACTION_DATA_ACQUISITION_SET: - convert_bosdyn_msgs_action_data_acquisition_to_proto(ros_msg.data_acquisition, proto.data_acquisition) - if ros_msg.action_choice == ros_msg.ACTION_REMOTE_GRPC_SET: - convert_bosdyn_msgs_action_remote_grpc_to_proto(ros_msg.remote_grpc, proto.remote_grpc) - if ros_msg.action_choice == ros_msg.ACTION_NODE_SET: - convert_bosdyn_msgs_node_to_proto(ros_msg.node, proto.node) - - -def convert_proto_to_bosdyn_msgs_action(proto: "bosdyn.api.autowalk.walks_pb2.Action", ros_msg: "bosdyn_msgs.msgs.Action") -> None: - convert_proto_to_bosdyn_msgs_action_one_of_action(proto, ros_msg.action) - - -def convert_bosdyn_msgs_action_to_proto(ros_msg: "bosdyn_msgs.msgs.Action", proto: "bosdyn.api.autowalk.walks_pb2.Action") -> None: - proto.Clear() - convert_bosdyn_msgs_action_one_of_action_to_proto(ros_msg.action, proto) - - -def convert_proto_to_bosdyn_msgs_action_wrapper_robot_body_sit(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.RobotBodySit", ros_msg: "bosdyn_msgs.msgs.ActionWrapperRobotBodySit") -> None: - pass - - -def convert_bosdyn_msgs_action_wrapper_robot_body_sit_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperRobotBodySit", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.RobotBodySit") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_action_wrapper_robot_body_pose(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.RobotBodyPose", ros_msg: "bosdyn_msgs.msgs.ActionWrapperRobotBodyPose") -> None: - convert_proto_to_geometry_msgs_pose(proto.target_tform_body, ros_msg.target_tform_body) - ros_msg.target_tform_body_is_set = proto.HasField("target_tform_body") - - -def convert_bosdyn_msgs_action_wrapper_robot_body_pose_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperRobotBodyPose", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.RobotBodyPose") -> None: - proto.Clear() - if ros_msg.target_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.target_tform_body, proto.target_tform_body) - - -def convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_led(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamLed", ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamLed") -> None: - from bosdyn_msgs.msg import KeyInt32ValueFloat32 - ros_msg.brightnesses = [] - for _item in proto.brightnesses: - ros_msg.brightnesses.append(KeyInt32ValueFloat32()) - ros_msg.brightnesses[-1].key = _item - ros_msg.brightnesses[-1].value = proto.brightnesses[_item] - - -def convert_bosdyn_msgs_action_wrapper_spot_cam_led_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamLed", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamLed") -> None: - proto.Clear() - for _item in ros_msg.brightnesses: - proto.brightnesses[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_ptz(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamPtz", ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamPtz") -> None: - convert_proto_to_bosdyn_msgs_ptz_position(proto.ptz_position, ros_msg.ptz_position) - ros_msg.ptz_position_is_set = proto.HasField("ptz_position") - - -def convert_bosdyn_msgs_action_wrapper_spot_cam_ptz_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamPtz", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamPtz") -> None: - proto.Clear() - if ros_msg.ptz_position_is_set: - convert_bosdyn_msgs_ptz_position_to_proto(ros_msg.ptz_position, proto.ptz_position) - - -def convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_one_of_reference(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment.Alignment", ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignmentAlignmentOneOfReference") -> None: - if proto.HasField("scene_object_id"): - ros_msg.reference_choice = ros_msg.REFERENCE_SCENE_OBJECT_ID_SET - ros_msg.scene_object_id = proto.scene_object_id - - -def convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_one_of_reference_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignmentAlignmentOneOfReference", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment.Alignment") -> None: - proto.ClearField("reference") - if ros_msg.reference_choice == ros_msg.REFERENCE_SCENE_OBJECT_ID_SET: - proto.scene_object_id = ros_msg.scene_object_id - - -def convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment.Alignment", ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignmentAlignment") -> None: - ros_msg.zoom = proto.zoom - ros_msg.sensor_id = proto.sensor_id - convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_one_of_reference(proto, ros_msg.reference) - ros_msg.is_skipped = proto.is_skipped - - -def convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignmentAlignment", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment.Alignment") -> None: - proto.Clear() - proto.zoom = ros_msg.zoom - proto.sensor_id = ros_msg.sensor_id - convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_one_of_reference_to_proto(ros_msg.reference, proto) - proto.is_skipped = ros_msg.is_skipped - - -def convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment", ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignment") -> None: - from bosdyn_msgs.msg import ActionWrapperSpotCamAlignmentAlignment - ros_msg.alignments = [] - for _item in proto.alignments: - ros_msg.alignments.append(ActionWrapperSpotCamAlignmentAlignment()) - convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment(_item, ros_msg.alignments[-1]) - convert_proto_to_geometry_msgs_pose(proto.target_tform_sensor, ros_msg.target_tform_sensor) - ros_msg.target_tform_sensor_is_set = proto.HasField("target_tform_sensor") - ros_msg.final_zoom = proto.final_zoom - ros_msg.target_sensor_ids = [] - for _item in proto.target_sensor_ids: - ros_msg.target_sensor_ids.append(_item) - - -def convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperSpotCamAlignment", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.SpotCamAlignment") -> None: - proto.Clear() - del proto.alignments[:] - for _item in ros_msg.alignments: - convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_alignment_to_proto(_item, proto.alignments.add()) - if ros_msg.target_tform_sensor_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.target_tform_sensor, proto.target_tform_sensor) - proto.final_zoom = ros_msg.final_zoom - del proto.target_sensor_ids[:] - for _item in ros_msg.target_sensor_ids: - proto.target_sensor_ids.append(_item) - - -def convert_proto_to_bosdyn_msgs_action_wrapper_arm_sensor_pointing(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.ArmSensorPointing", ros_msg: "bosdyn_msgs.msgs.ActionWrapperArmSensorPointing") -> None: - convert_proto_to_bosdyn_msgs_arm_joint_trajectory(proto.joint_trajectory, ros_msg.joint_trajectory) - ros_msg.joint_trajectory_is_set = proto.HasField("joint_trajectory") - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.pose_trajectory_rt_target, ros_msg.pose_trajectory_rt_target) - ros_msg.pose_trajectory_rt_target_is_set = proto.HasField("pose_trajectory_rt_target") - convert_proto_to_bosdyn_msgs_se2_pose(proto.target_tform_measured_offset, ros_msg.target_tform_measured_offset) - ros_msg.target_tform_measured_offset_is_set = proto.HasField("target_tform_measured_offset") - convert_proto_to_bosdyn_msgs_body_control_params_body_assist_for_manipulation(proto.body_assist_params, ros_msg.body_assist_params) - ros_msg.body_assist_params_is_set = proto.HasField("body_assist_params") - ros_msg.force_stow_override = proto.force_stow_override - - -def convert_bosdyn_msgs_action_wrapper_arm_sensor_pointing_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperArmSensorPointing", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.ArmSensorPointing") -> None: - proto.Clear() - if ros_msg.joint_trajectory_is_set: - convert_bosdyn_msgs_arm_joint_trajectory_to_proto(ros_msg.joint_trajectory, proto.joint_trajectory) - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - if ros_msg.pose_trajectory_rt_target_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.pose_trajectory_rt_target, proto.pose_trajectory_rt_target) - if ros_msg.target_tform_measured_offset_is_set: - convert_bosdyn_msgs_se2_pose_to_proto(ros_msg.target_tform_measured_offset, proto.target_tform_measured_offset) - if ros_msg.body_assist_params_is_set: - convert_bosdyn_msgs_body_control_params_body_assist_for_manipulation_to_proto(ros_msg.body_assist_params, proto.body_assist_params) - proto.force_stow_override = ros_msg.force_stow_override - - -def convert_proto_to_bosdyn_msgs_action_wrapper_gripper_camera_params(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCameraParams", ros_msg: "bosdyn_msgs.msgs.ActionWrapperGripperCameraParams") -> None: - convert_proto_to_bosdyn_msgs_gripper_camera_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_action_wrapper_gripper_camera_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperGripperCameraParams", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCameraParams") -> None: - proto.Clear() - if ros_msg.params_is_set: - convert_bosdyn_msgs_gripper_camera_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_action_wrapper_gripper_command(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCommand", ros_msg: "bosdyn_msgs.msgs.ActionWrapperGripperCommand") -> None: - convert_proto_to_bosdyn_msgs_gripper_command_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - - -def convert_bosdyn_msgs_action_wrapper_gripper_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapperGripperCommand", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper.GripperCommand") -> None: - proto.Clear() - if ros_msg.request_is_set: - convert_bosdyn_msgs_gripper_command_request_to_proto(ros_msg.request, proto.request) - - -def convert_proto_to_bosdyn_msgs_action_wrapper(proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper", ros_msg: "bosdyn_msgs.msgs.ActionWrapper") -> None: - convert_proto_to_bosdyn_msgs_action_wrapper_robot_body_sit(proto.robot_body_sit, ros_msg.robot_body_sit) - ros_msg.robot_body_sit_is_set = proto.HasField("robot_body_sit") - convert_proto_to_bosdyn_msgs_action_wrapper_robot_body_pose(proto.robot_body_pose, ros_msg.robot_body_pose) - ros_msg.robot_body_pose_is_set = proto.HasField("robot_body_pose") - convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_led(proto.spot_cam_led, ros_msg.spot_cam_led) - ros_msg.spot_cam_led_is_set = proto.HasField("spot_cam_led") - convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_ptz(proto.spot_cam_ptz, ros_msg.spot_cam_ptz) - ros_msg.spot_cam_ptz_is_set = proto.HasField("spot_cam_ptz") - convert_proto_to_bosdyn_msgs_action_wrapper_arm_sensor_pointing(proto.arm_sensor_pointing, ros_msg.arm_sensor_pointing) - ros_msg.arm_sensor_pointing_is_set = proto.HasField("arm_sensor_pointing") - convert_proto_to_bosdyn_msgs_action_wrapper_spot_cam_alignment(proto.spot_cam_alignment, ros_msg.spot_cam_alignment) - ros_msg.spot_cam_alignment_is_set = proto.HasField("spot_cam_alignment") - convert_proto_to_bosdyn_msgs_action_wrapper_gripper_camera_params(proto.gripper_camera_params, ros_msg.gripper_camera_params) - ros_msg.gripper_camera_params_is_set = proto.HasField("gripper_camera_params") - convert_proto_to_bosdyn_msgs_action_wrapper_gripper_command(proto.gripper_command, ros_msg.gripper_command) - ros_msg.gripper_command_is_set = proto.HasField("gripper_command") - - -def convert_bosdyn_msgs_action_wrapper_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionWrapper", proto: "bosdyn.api.autowalk.walks_pb2.ActionWrapper") -> None: - proto.Clear() - if ros_msg.robot_body_sit_is_set: - convert_bosdyn_msgs_action_wrapper_robot_body_sit_to_proto(ros_msg.robot_body_sit, proto.robot_body_sit) - if ros_msg.robot_body_pose_is_set: - convert_bosdyn_msgs_action_wrapper_robot_body_pose_to_proto(ros_msg.robot_body_pose, proto.robot_body_pose) - if ros_msg.spot_cam_led_is_set: - convert_bosdyn_msgs_action_wrapper_spot_cam_led_to_proto(ros_msg.spot_cam_led, proto.spot_cam_led) - if ros_msg.spot_cam_ptz_is_set: - convert_bosdyn_msgs_action_wrapper_spot_cam_ptz_to_proto(ros_msg.spot_cam_ptz, proto.spot_cam_ptz) - if ros_msg.arm_sensor_pointing_is_set: - convert_bosdyn_msgs_action_wrapper_arm_sensor_pointing_to_proto(ros_msg.arm_sensor_pointing, proto.arm_sensor_pointing) - if ros_msg.spot_cam_alignment_is_set: - convert_bosdyn_msgs_action_wrapper_spot_cam_alignment_to_proto(ros_msg.spot_cam_alignment, proto.spot_cam_alignment) - if ros_msg.gripper_camera_params_is_set: - convert_bosdyn_msgs_action_wrapper_gripper_camera_params_to_proto(ros_msg.gripper_camera_params, proto.gripper_camera_params) - if ros_msg.gripper_command_is_set: - convert_bosdyn_msgs_action_wrapper_gripper_command_to_proto(ros_msg.gripper_command, proto.gripper_command) - - -def convert_proto_to_bosdyn_msgs_failure_behavior_safe_power_off(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.SafePowerOff", ros_msg: "bosdyn_msgs.msgs.FailureBehaviorSafePowerOff") -> None: - convert_proto_to_bosdyn_msgs_safe_power_off_command_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - - -def convert_bosdyn_msgs_failure_behavior_safe_power_off_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehaviorSafePowerOff", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.SafePowerOff") -> None: - proto.Clear() - if ros_msg.request_is_set: - convert_bosdyn_msgs_safe_power_off_command_request_to_proto(ros_msg.request, proto.request) - - -def convert_proto_to_bosdyn_msgs_failure_behavior_proceed_if_able(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ProceedIfAble", ros_msg: "bosdyn_msgs.msgs.FailureBehaviorProceedIfAble") -> None: - pass - - -def convert_bosdyn_msgs_failure_behavior_proceed_if_able_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehaviorProceedIfAble", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ProceedIfAble") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_failure_behavior_return_to_start_and_try_again_later(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ReturnToStartAndTryAgainLater", ros_msg: "bosdyn_msgs.msgs.FailureBehaviorReturnToStartAndTryAgainLater") -> None: - convert_proto_to_builtin_interfaces_duration(proto.try_again_delay, ros_msg.try_again_delay) - ros_msg.try_again_delay_is_set = proto.HasField("try_again_delay") - - -def convert_bosdyn_msgs_failure_behavior_return_to_start_and_try_again_later_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehaviorReturnToStartAndTryAgainLater", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ReturnToStartAndTryAgainLater") -> None: - proto.Clear() - if ros_msg.try_again_delay_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.try_again_delay, proto.try_again_delay) - - -def convert_proto_to_bosdyn_msgs_failure_behavior_return_to_start_and_terminate(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ReturnToStartAndTerminate", ros_msg: "bosdyn_msgs.msgs.FailureBehaviorReturnToStartAndTerminate") -> None: - pass - - -def convert_bosdyn_msgs_failure_behavior_return_to_start_and_terminate_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehaviorReturnToStartAndTerminate", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior.ReturnToStartAndTerminate") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_failure_behavior_one_of_default_behavior(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior", ros_msg: "bosdyn_msgs.msgs.FailureBehaviorOneOfDefaultBehavior") -> None: - if proto.HasField("safe_power_off"): - ros_msg.default_behavior_choice = ros_msg.DEFAULT_BEHAVIOR_SAFE_POWER_OFF_SET - convert_proto_to_bosdyn_msgs_failure_behavior_safe_power_off(proto.safe_power_off, ros_msg.safe_power_off) - if proto.HasField("proceed_if_able"): - ros_msg.default_behavior_choice = ros_msg.DEFAULT_BEHAVIOR_PROCEED_IF_ABLE_SET - convert_proto_to_bosdyn_msgs_failure_behavior_proceed_if_able(proto.proceed_if_able, ros_msg.proceed_if_able) - if proto.HasField("return_to_start_and_try_again_later"): - ros_msg.default_behavior_choice = ros_msg.DEFAULT_BEHAVIOR_RETURN_TO_START_AND_TRY_AGAIN_LATER_SET - convert_proto_to_bosdyn_msgs_failure_behavior_return_to_start_and_try_again_later(proto.return_to_start_and_try_again_later, ros_msg.return_to_start_and_try_again_later) - if proto.HasField("return_to_start_and_terminate"): - ros_msg.default_behavior_choice = ros_msg.DEFAULT_BEHAVIOR_RETURN_TO_START_AND_TERMINATE_SET - convert_proto_to_bosdyn_msgs_failure_behavior_return_to_start_and_terminate(proto.return_to_start_and_terminate, ros_msg.return_to_start_and_terminate) - - -def convert_bosdyn_msgs_failure_behavior_one_of_default_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehaviorOneOfDefaultBehavior", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior") -> None: - proto.ClearField("default_behavior") - if ros_msg.default_behavior_choice == ros_msg.DEFAULT_BEHAVIOR_SAFE_POWER_OFF_SET: - convert_bosdyn_msgs_failure_behavior_safe_power_off_to_proto(ros_msg.safe_power_off, proto.safe_power_off) - if ros_msg.default_behavior_choice == ros_msg.DEFAULT_BEHAVIOR_PROCEED_IF_ABLE_SET: - convert_bosdyn_msgs_failure_behavior_proceed_if_able_to_proto(ros_msg.proceed_if_able, proto.proceed_if_able) - if ros_msg.default_behavior_choice == ros_msg.DEFAULT_BEHAVIOR_RETURN_TO_START_AND_TRY_AGAIN_LATER_SET: - convert_bosdyn_msgs_failure_behavior_return_to_start_and_try_again_later_to_proto(ros_msg.return_to_start_and_try_again_later, proto.return_to_start_and_try_again_later) - if ros_msg.default_behavior_choice == ros_msg.DEFAULT_BEHAVIOR_RETURN_TO_START_AND_TERMINATE_SET: - convert_bosdyn_msgs_failure_behavior_return_to_start_and_terminate_to_proto(ros_msg.return_to_start_and_terminate, proto.return_to_start_and_terminate) - - -def convert_proto_to_bosdyn_msgs_failure_behavior(proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior", ros_msg: "bosdyn_msgs.msgs.FailureBehavior") -> None: - ros_msg.retry_count = proto.retry_count - convert_proto_to_builtin_interfaces_duration(proto.prompt_duration, ros_msg.prompt_duration) - ros_msg.prompt_duration_is_set = proto.HasField("prompt_duration") - convert_proto_to_bosdyn_msgs_failure_behavior_one_of_default_behavior(proto, ros_msg.default_behavior) - - -def convert_bosdyn_msgs_failure_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.FailureBehavior", proto: "bosdyn.api.autowalk.walks_pb2.FailureBehavior") -> None: - proto.Clear() - proto.retry_count = ros_msg.retry_count - if ros_msg.prompt_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.prompt_duration, proto.prompt_duration) - convert_bosdyn_msgs_failure_behavior_one_of_default_behavior_to_proto(ros_msg.default_behavior, proto) - - -def convert_proto_to_bosdyn_msgs_battery_monitor(proto: "bosdyn.api.autowalk.walks_pb2.BatteryMonitor", ros_msg: "bosdyn_msgs.msgs.BatteryMonitor") -> None: - ros_msg.battery_start_threshold = proto.battery_start_threshold - ros_msg.battery_stop_threshold = proto.battery_stop_threshold - - -def convert_bosdyn_msgs_battery_monitor_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryMonitor", proto: "bosdyn.api.autowalk.walks_pb2.BatteryMonitor") -> None: - proto.Clear() - proto.battery_start_threshold = ros_msg.battery_start_threshold - proto.battery_stop_threshold = ros_msg.battery_stop_threshold - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_status_status(proto: "bosdyn.api.basic_command_pb2.RobotCommandFeedbackStatus.Status", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackStatusStatus") -> None: - pass - - -def convert_bosdyn_msgs_robot_command_feedback_status_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackStatusStatus", proto: "bosdyn.api.basic_command_pb2.RobotCommandFeedbackStatus.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.RobotCommandFeedbackStatus", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_robot_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.RobotCommandFeedbackStatus") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_battery_change_pose_command_request_direction_hint(proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Request.DirectionHint", ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandRequestDirectionHint") -> None: - pass - - -def convert_bosdyn_msgs_battery_change_pose_command_request_direction_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandRequestDirectionHint", proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Request.DirectionHint") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_battery_change_pose_command_request(proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Request", ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandRequest") -> None: - ros_msg.direction_hint.value = proto.direction_hint - - -def convert_bosdyn_msgs_battery_change_pose_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandRequest", proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Request") -> None: - proto.Clear() - proto.direction_hint = ros_msg.direction_hint.value - - -def convert_proto_to_bosdyn_msgs_battery_change_pose_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_battery_change_pose_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_battery_change_pose_command_feedback(proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_battery_change_pose_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommandFeedback", proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_battery_change_pose_command(proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand", ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommand") -> None: - pass - - -def convert_bosdyn_msgs_battery_change_pose_command_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryChangePoseCommand", proto: "bosdyn.api.basic_command_pb2.BatteryChangePoseCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_self_right_command_request(proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Request", ros_msg: "bosdyn_msgs.msgs.SelfRightCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_self_right_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SelfRightCommandRequest", proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_self_right_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.SelfRightCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_self_right_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SelfRightCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_self_right_command_feedback(proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SelfRightCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_self_right_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SelfRightCommandFeedback", proto: "bosdyn.api.basic_command_pb2.SelfRightCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_self_right_command(proto: "bosdyn.api.basic_command_pb2.SelfRightCommand", ros_msg: "bosdyn_msgs.msgs.SelfRightCommand") -> None: - pass - - -def convert_bosdyn_msgs_self_right_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SelfRightCommand", proto: "bosdyn.api.basic_command_pb2.SelfRightCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stop_command_request(proto: "bosdyn.api.basic_command_pb2.StopCommand.Request", ros_msg: "bosdyn_msgs.msgs.StopCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_stop_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StopCommandRequest", proto: "bosdyn.api.basic_command_pb2.StopCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stop_command_feedback(proto: "bosdyn.api.basic_command_pb2.StopCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.StopCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_stop_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.StopCommandFeedback", proto: "bosdyn.api.basic_command_pb2.StopCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stop_command(proto: "bosdyn.api.basic_command_pb2.StopCommand", ros_msg: "bosdyn_msgs.msgs.StopCommand") -> None: - pass - - -def convert_bosdyn_msgs_stop_command_to_proto(ros_msg: "bosdyn_msgs.msgs.StopCommand", proto: "bosdyn.api.basic_command_pb2.StopCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_freeze_command_request(proto: "bosdyn.api.basic_command_pb2.FreezeCommand.Request", ros_msg: "bosdyn_msgs.msgs.FreezeCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_freeze_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.FreezeCommandRequest", proto: "bosdyn.api.basic_command_pb2.FreezeCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_freeze_command_feedback(proto: "bosdyn.api.basic_command_pb2.FreezeCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.FreezeCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_freeze_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.FreezeCommandFeedback", proto: "bosdyn.api.basic_command_pb2.FreezeCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_freeze_command(proto: "bosdyn.api.basic_command_pb2.FreezeCommand", ros_msg: "bosdyn_msgs.msgs.FreezeCommand") -> None: - pass - - -def convert_bosdyn_msgs_freeze_command_to_proto(ros_msg: "bosdyn_msgs.msgs.FreezeCommand", proto: "bosdyn.api.basic_command_pb2.FreezeCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_safe_power_off_command_request_unsafe_action(proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Request.UnsafeAction", ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandRequestUnsafeAction") -> None: - pass - - -def convert_bosdyn_msgs_safe_power_off_command_request_unsafe_action_to_proto(ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandRequestUnsafeAction", proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Request.UnsafeAction") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_safe_power_off_command_request(proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Request", ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandRequest") -> None: - ros_msg.unsafe_action.value = proto.unsafe_action - - -def convert_bosdyn_msgs_safe_power_off_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandRequest", proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Request") -> None: - proto.Clear() - proto.unsafe_action = ros_msg.unsafe_action.value - - -def convert_proto_to_bosdyn_msgs_safe_power_off_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_safe_power_off_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_safe_power_off_command_feedback(proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_safe_power_off_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommandFeedback", proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_safe_power_off_command(proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand", ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommand") -> None: - pass - - -def convert_bosdyn_msgs_safe_power_off_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SafePowerOffCommand", proto: "bosdyn.api.basic_command_pb2.SafePowerOffCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_command_request(proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Request", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandRequest") -> None: - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.se2_frame_name = proto.se2_frame_name - convert_proto_to_bosdyn_msgs_se2_trajectory(proto.trajectory, ros_msg.trajectory) - ros_msg.trajectory_is_set = proto.HasField("trajectory") - - -def convert_bosdyn_msgs_se2_trajectory_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandRequest", proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Request") -> None: - proto.Clear() - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.se2_frame_name = ros_msg.se2_frame_name - if ros_msg.trajectory_is_set: - convert_bosdyn_msgs_se2_trajectory_to_proto(ros_msg.trajectory, proto.trajectory) - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_se2_trajectory_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_command_feedback_body_movement_status(proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback.BodyMovementStatus", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedbackBodyMovementStatus") -> None: - pass - - -def convert_bosdyn_msgs_se2_trajectory_command_feedback_body_movement_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedbackBodyMovementStatus", proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback.BodyMovementStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_command_feedback(proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.body_movement_status.value = proto.body_movement_status - - -def convert_bosdyn_msgs_se2_trajectory_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommandFeedback", proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.body_movement_status = ros_msg.body_movement_status.value - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_command(proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommand") -> None: - pass - - -def convert_bosdyn_msgs_se2_trajectory_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryCommand", proto: "bosdyn.api.basic_command_pb2.SE2TrajectoryCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_se2_velocity_command_request(proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand.Request", ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommandRequest") -> None: - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.se2_frame_name = proto.se2_frame_name - convert_proto_to_bosdyn_msgs_se2_velocity(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - convert_proto_to_bosdyn_msgs_se2_velocity(proto.slew_rate_limit, ros_msg.slew_rate_limit) - ros_msg.slew_rate_limit_is_set = proto.HasField("slew_rate_limit") - - -def convert_bosdyn_msgs_se2_velocity_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommandRequest", proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand.Request") -> None: - proto.Clear() - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.se2_frame_name = ros_msg.se2_frame_name - if ros_msg.velocity_is_set: - convert_bosdyn_msgs_se2_velocity_to_proto(ros_msg.velocity, proto.velocity) - if ros_msg.slew_rate_limit_is_set: - convert_bosdyn_msgs_se2_velocity_to_proto(ros_msg.slew_rate_limit, proto.slew_rate_limit) - - -def convert_proto_to_bosdyn_msgs_se2_velocity_command_feedback(proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_se2_velocity_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommandFeedback", proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_se2_velocity_command(proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand", ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommand") -> None: - pass - - -def convert_bosdyn_msgs_se2_velocity_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2VelocityCommand", proto: "bosdyn.api.basic_command_pb2.SE2VelocityCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_sit_command_request(proto: "bosdyn.api.basic_command_pb2.SitCommand.Request", ros_msg: "bosdyn_msgs.msgs.SitCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_sit_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SitCommandRequest", proto: "bosdyn.api.basic_command_pb2.SitCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_sit_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.SitCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.SitCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_sit_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SitCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.SitCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_sit_command_feedback(proto: "bosdyn.api.basic_command_pb2.SitCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SitCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_sit_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SitCommandFeedback", proto: "bosdyn.api.basic_command_pb2.SitCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_sit_command(proto: "bosdyn.api.basic_command_pb2.SitCommand", ros_msg: "bosdyn_msgs.msgs.SitCommand") -> None: - pass - - -def convert_bosdyn_msgs_sit_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SitCommand", proto: "bosdyn.api.basic_command_pb2.SitCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stand_command_request(proto: "bosdyn.api.basic_command_pb2.StandCommand.Request", ros_msg: "bosdyn_msgs.msgs.StandCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_stand_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StandCommandRequest", proto: "bosdyn.api.basic_command_pb2.StandCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stand_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.StandCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_stand_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StandCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stand_command_feedback_standing_state(proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback.StandingState", ros_msg: "bosdyn_msgs.msgs.StandCommandFeedbackStandingState") -> None: - pass - - -def convert_bosdyn_msgs_stand_command_feedback_standing_state_to_proto(ros_msg: "bosdyn_msgs.msgs.StandCommandFeedbackStandingState", proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback.StandingState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stand_command_feedback(proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.StandCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.standing_state.value = proto.standing_state - - -def convert_bosdyn_msgs_stand_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.StandCommandFeedback", proto: "bosdyn.api.basic_command_pb2.StandCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.standing_state = ros_msg.standing_state.value - - -def convert_proto_to_bosdyn_msgs_stand_command(proto: "bosdyn.api.basic_command_pb2.StandCommand", ros_msg: "bosdyn_msgs.msgs.StandCommand") -> None: - pass - - -def convert_bosdyn_msgs_stand_command_to_proto(ros_msg: "bosdyn_msgs.msgs.StandCommand", proto: "bosdyn.api.basic_command_pb2.StandCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stance_command_request(proto: "bosdyn.api.basic_command_pb2.StanceCommand.Request", ros_msg: "bosdyn_msgs.msgs.StanceCommandRequest") -> None: - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - convert_proto_to_bosdyn_msgs_stance(proto.stance, ros_msg.stance) - ros_msg.stance_is_set = proto.HasField("stance") - - -def convert_bosdyn_msgs_stance_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StanceCommandRequest", proto: "bosdyn.api.basic_command_pb2.StanceCommand.Request") -> None: - proto.Clear() - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - if ros_msg.stance_is_set: - convert_bosdyn_msgs_stance_to_proto(ros_msg.stance, proto.stance) - - -def convert_proto_to_bosdyn_msgs_stance_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.StanceCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.StanceCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_stance_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StanceCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.StanceCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stance_command_feedback(proto: "bosdyn.api.basic_command_pb2.StanceCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.StanceCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_stance_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.StanceCommandFeedback", proto: "bosdyn.api.basic_command_pb2.StanceCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_stance_command(proto: "bosdyn.api.basic_command_pb2.StanceCommand", ros_msg: "bosdyn_msgs.msgs.StanceCommand") -> None: - pass - - -def convert_bosdyn_msgs_stance_command_to_proto(ros_msg: "bosdyn_msgs.msgs.StanceCommand", proto: "bosdyn.api.basic_command_pb2.StanceCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stance(proto: "bosdyn.api.basic_command_pb2.Stance", ros_msg: "bosdyn_msgs.msgs.Stance") -> None: - ros_msg.se2_frame_name = proto.se2_frame_name - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsVec2 - ros_msg.foot_positions = [] - for _item in proto.foot_positions: - ros_msg.foot_positions.append(KeyStringValueBosdynMsgsVec2()) - ros_msg.foot_positions[-1].key = _item - convert_proto_to_bosdyn_msgs_vec2(proto.foot_positions[_item], ros_msg.foot_positions[-1].value) - ros_msg.accuracy = proto.accuracy - - -def convert_bosdyn_msgs_stance_to_proto(ros_msg: "bosdyn_msgs.msgs.Stance", proto: "bosdyn.api.basic_command_pb2.Stance") -> None: - proto.Clear() - proto.se2_frame_name = ros_msg.se2_frame_name - for _item in ros_msg.foot_positions: - convert_bosdyn_msgs_vec2_to_proto(_item.value, proto.foot_positions[_item.key]) - proto.accuracy = ros_msg.accuracy - - -def convert_proto_to_bosdyn_msgs_follow_arm_command_request(proto: "bosdyn.api.basic_command_pb2.FollowArmCommand.Request", ros_msg: "bosdyn_msgs.msgs.FollowArmCommandRequest") -> None: - convert_proto_to_geometry_msgs_vector3(proto.body_offset_from_hand, ros_msg.body_offset_from_hand) - ros_msg.body_offset_from_hand_is_set = proto.HasField("body_offset_from_hand") - - -def convert_bosdyn_msgs_follow_arm_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.FollowArmCommandRequest", proto: "bosdyn.api.basic_command_pb2.FollowArmCommand.Request") -> None: - proto.Clear() - if ros_msg.body_offset_from_hand_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.body_offset_from_hand, proto.body_offset_from_hand) - - -def convert_proto_to_bosdyn_msgs_follow_arm_command_feedback(proto: "bosdyn.api.basic_command_pb2.FollowArmCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.FollowArmCommandFeedback") -> None: - pass - - -def convert_bosdyn_msgs_follow_arm_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.FollowArmCommandFeedback", proto: "bosdyn.api.basic_command_pb2.FollowArmCommand.Feedback") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_follow_arm_command(proto: "bosdyn.api.basic_command_pb2.FollowArmCommand", ros_msg: "bosdyn_msgs.msgs.FollowArmCommand") -> None: - pass - - -def convert_bosdyn_msgs_follow_arm_command_to_proto(ros_msg: "bosdyn_msgs.msgs.FollowArmCommand", proto: "bosdyn.api.basic_command_pb2.FollowArmCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_drag_command_request(proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Request", ros_msg: "bosdyn_msgs.msgs.ArmDragCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_arm_drag_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmDragCommandRequest", proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_arm_drag_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ArmDragCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_arm_drag_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmDragCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_arm_drag_command_feedback(proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ArmDragCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_arm_drag_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmDragCommandFeedback", proto: "bosdyn.api.basic_command_pb2.ArmDragCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_arm_drag_command(proto: "bosdyn.api.basic_command_pb2.ArmDragCommand", ros_msg: "bosdyn_msgs.msgs.ArmDragCommand") -> None: - pass - - -def convert_bosdyn_msgs_arm_drag_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ArmDragCommand", proto: "bosdyn.api.basic_command_pb2.ArmDragCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_speed(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestOneOfTaskSpeed") -> None: - if proto.HasField("tangential_speed"): - ros_msg.task_speed_choice = ros_msg.TASK_SPEED_TANGENTIAL_SPEED_SET - ros_msg.tangential_speed = proto.tangential_speed - if proto.HasField("rotational_speed"): - ros_msg.task_speed_choice = ros_msg.TASK_SPEED_ROTATIONAL_SPEED_SET - ros_msg.rotational_speed = proto.rotational_speed - - -def convert_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_speed_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestOneOfTaskSpeed", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request") -> None: - proto.ClearField("task_speed") - if ros_msg.task_speed_choice == ros_msg.TASK_SPEED_TANGENTIAL_SPEED_SET: - proto.tangential_speed = ros_msg.tangential_speed - if ros_msg.task_speed_choice == ros_msg.TASK_SPEED_ROTATIONAL_SPEED_SET: - proto.rotational_speed = ros_msg.rotational_speed - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_task_type(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request.TaskType", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestTaskType") -> None: - pass - - -def convert_bosdyn_msgs_constrained_manipulation_command_request_task_type_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestTaskType", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request.TaskType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_control_mode(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request.ControlMode", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestControlMode") -> None: - pass - - -def convert_bosdyn_msgs_constrained_manipulation_command_request_control_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestControlMode", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request.ControlMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_target_position(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestOneOfTaskTargetPosition") -> None: - if proto.HasField("target_linear_position"): - ros_msg.task_target_position_choice = ros_msg.TASK_TARGET_POSITION_TARGET_LINEAR_POSITION_SET - ros_msg.target_linear_position = proto.target_linear_position - if proto.HasField("target_angle"): - ros_msg.task_target_position_choice = ros_msg.TASK_TARGET_POSITION_TARGET_ANGLE_SET - ros_msg.target_angle = proto.target_angle - - -def convert_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_target_position_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequestOneOfTaskTargetPosition", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request") -> None: - proto.ClearField("task_target_position") - if ros_msg.task_target_position_choice == ros_msg.TASK_TARGET_POSITION_TARGET_LINEAR_POSITION_SET: - proto.target_linear_position = ros_msg.target_linear_position - if ros_msg.task_target_position_choice == ros_msg.TASK_TARGET_POSITION_TARGET_ANGLE_SET: - proto.target_angle = ros_msg.target_angle - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequest") -> None: - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_wrench(proto.init_wrench_direction_in_frame_name, ros_msg.init_wrench_direction_in_frame_name) - ros_msg.init_wrench_direction_in_frame_name_is_set = proto.HasField("init_wrench_direction_in_frame_name") - convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_speed(proto, ros_msg.task_speed) - ros_msg.force_limit = proto.force_limit.value - ros_msg.force_limit_is_set = proto.HasField("force_limit") - ros_msg.torque_limit = proto.torque_limit.value - ros_msg.torque_limit_is_set = proto.HasField("torque_limit") - ros_msg.task_type.value = proto.task_type - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.enable_robot_locomotion = proto.enable_robot_locomotion.value - ros_msg.enable_robot_locomotion_is_set = proto.HasField("enable_robot_locomotion") - ros_msg.control_mode.value = proto.control_mode - convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_target_position(proto, ros_msg.task_target_position) - ros_msg.accel_limit = proto.accel_limit.value - ros_msg.accel_limit_is_set = proto.HasField("accel_limit") - ros_msg.reset_estimator = proto.reset_estimator.value - ros_msg.reset_estimator_is_set = proto.HasField("reset_estimator") - - -def convert_bosdyn_msgs_constrained_manipulation_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandRequest", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Request") -> None: - proto.Clear() - proto.frame_name = ros_msg.frame_name - if ros_msg.init_wrench_direction_in_frame_name_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.init_wrench_direction_in_frame_name, proto.init_wrench_direction_in_frame_name) - convert_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_speed_to_proto(ros_msg.task_speed, proto) - if ros_msg.force_limit_is_set: - convert_float64_to_proto(ros_msg.force_limit, proto.force_limit) - if ros_msg.torque_limit_is_set: - convert_float64_to_proto(ros_msg.torque_limit, proto.torque_limit) - proto.task_type = ros_msg.task_type.value - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - if ros_msg.enable_robot_locomotion_is_set: - convert_bool_to_proto(ros_msg.enable_robot_locomotion, proto.enable_robot_locomotion) - proto.control_mode = ros_msg.control_mode.value - convert_bosdyn_msgs_constrained_manipulation_command_request_one_of_task_target_position_to_proto(ros_msg.task_target_position, proto) - if ros_msg.accel_limit_is_set: - convert_float64_to_proto(ros_msg.accel_limit, proto.accel_limit) - if ros_msg.reset_estimator_is_set: - convert_bool_to_proto(ros_msg.reset_estimator, proto.reset_estimator) - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_feedback_status(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_constrained_manipulation_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandFeedbackStatus", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command_feedback(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandFeedback") -> None: - ros_msg.status.value = proto.status - convert_proto_to_geometry_msgs_wrench(proto.desired_wrench_odom_frame, ros_msg.desired_wrench_odom_frame) - ros_msg.desired_wrench_odom_frame_is_set = proto.HasField("desired_wrench_odom_frame") - ros_msg.estimation_activated = proto.estimation_activated.value - ros_msg.estimation_activated_is_set = proto.HasField("estimation_activated") - - -def convert_bosdyn_msgs_constrained_manipulation_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommandFeedback", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - if ros_msg.desired_wrench_odom_frame_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.desired_wrench_odom_frame, proto.desired_wrench_odom_frame) - if ros_msg.estimation_activated_is_set: - convert_bool_to_proto(ros_msg.estimation_activated, proto.estimation_activated) - - -def convert_proto_to_bosdyn_msgs_constrained_manipulation_command(proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand", ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommand") -> None: - pass - - -def convert_bosdyn_msgs_constrained_manipulation_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstrainedManipulationCommand", proto: "bosdyn.api.basic_command_pb2.ConstrainedManipulationCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_descriptor_block_one_of_descriptor_type(proto: "bosdyn.api.bddf_pb2.DescriptorBlock.DescriptorType", ros_msg: "bosdyn_msgs.msgs.DescriptorBlockOneOfDescriptorType") -> None: - if proto.HasField("file_descriptor"): - ros_msg.descriptor_type_choice = ros_msg.DESCRIPTORTYPE_FILE_DESCRIPTOR_SET - convert_proto_to_bosdyn_msgs_file_format_descriptor(proto.file_descriptor, ros_msg.file_descriptor) - if proto.HasField("series_descriptor"): - ros_msg.descriptor_type_choice = ros_msg.DESCRIPTORTYPE_SERIES_DESCRIPTOR_SET - convert_proto_to_bosdyn_msgs_series_descriptor(proto.series_descriptor, ros_msg.series_descriptor) - if proto.HasField("series_block_index"): - ros_msg.descriptor_type_choice = ros_msg.DESCRIPTORTYPE_SERIES_BLOCK_INDEX_SET - convert_proto_to_bosdyn_msgs_series_block_index(proto.series_block_index, ros_msg.series_block_index) - if proto.HasField("file_index"): - ros_msg.descriptor_type_choice = ros_msg.DESCRIPTORTYPE_FILE_INDEX_SET - convert_proto_to_bosdyn_msgs_file_index(proto.file_index, ros_msg.file_index) - - -def convert_bosdyn_msgs_descriptor_block_one_of_descriptor_type_to_proto(ros_msg: "bosdyn_msgs.msgs.DescriptorBlockOneOfDescriptorType", proto: "bosdyn.api.bddf_pb2.DescriptorBlock.DescriptorType") -> None: - proto.ClearField("DescriptorType") - if ros_msg.descriptor_type_choice == ros_msg.DESCRIPTORTYPE_FILE_DESCRIPTOR_SET: - convert_bosdyn_msgs_file_format_descriptor_to_proto(ros_msg.file_descriptor, proto.file_descriptor) - if ros_msg.descriptor_type_choice == ros_msg.DESCRIPTORTYPE_SERIES_DESCRIPTOR_SET: - convert_bosdyn_msgs_series_descriptor_to_proto(ros_msg.series_descriptor, proto.series_descriptor) - if ros_msg.descriptor_type_choice == ros_msg.DESCRIPTORTYPE_SERIES_BLOCK_INDEX_SET: - convert_bosdyn_msgs_series_block_index_to_proto(ros_msg.series_block_index, proto.series_block_index) - if ros_msg.descriptor_type_choice == ros_msg.DESCRIPTORTYPE_FILE_INDEX_SET: - convert_bosdyn_msgs_file_index_to_proto(ros_msg.file_index, proto.file_index) - - -def convert_proto_to_bosdyn_msgs_descriptor_block(proto: "bosdyn.api.bddf_pb2.DescriptorBlock", ros_msg: "bosdyn_msgs.msgs.DescriptorBlock") -> None: - convert_proto_to_bosdyn_msgs_descriptor_block_one_of_descriptor_type(proto, ros_msg.descriptor_type) - - -def convert_bosdyn_msgs_descriptor_block_to_proto(ros_msg: "bosdyn_msgs.msgs.DescriptorBlock", proto: "bosdyn.api.bddf_pb2.DescriptorBlock") -> None: - proto.Clear() - convert_bosdyn_msgs_descriptor_block_one_of_descriptor_type_to_proto(ros_msg.descriptor_type, proto) - - -def convert_proto_to_bosdyn_msgs_data_descriptor(proto: "bosdyn.api.bddf_pb2.DataDescriptor", ros_msg: "bosdyn_msgs.msgs.DataDescriptor") -> None: - ros_msg.series_index = proto.series_index - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.additional_indexes = [] - for _item in proto.additional_indexes: - ros_msg.additional_indexes.append(_item) - - -def convert_bosdyn_msgs_data_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.DataDescriptor", proto: "bosdyn.api.bddf_pb2.DataDescriptor") -> None: - proto.Clear() - proto.series_index = ros_msg.series_index - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - del proto.additional_indexes[:] - for _item in ros_msg.additional_indexes: - proto.additional_indexes.append(_item) - - -def convert_proto_to_bosdyn_msgs_file_format_descriptor_check_sum_type(proto: "bosdyn.api.bddf_pb2.FileFormatDescriptor.CheckSumType", ros_msg: "bosdyn_msgs.msgs.FileFormatDescriptorCheckSumType") -> None: - pass - - -def convert_bosdyn_msgs_file_format_descriptor_check_sum_type_to_proto(ros_msg: "bosdyn_msgs.msgs.FileFormatDescriptorCheckSumType", proto: "bosdyn.api.bddf_pb2.FileFormatDescriptor.CheckSumType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_file_format_descriptor(proto: "bosdyn.api.bddf_pb2.FileFormatDescriptor", ros_msg: "bosdyn_msgs.msgs.FileFormatDescriptor") -> None: - convert_proto_to_bosdyn_msgs_file_format_version(proto.version, ros_msg.version) - ros_msg.version_is_set = proto.HasField("version") - from bosdyn_msgs.msg import KeyStringValueString - ros_msg.annotations = [] - for _item in proto.annotations: - ros_msg.annotations.append(KeyStringValueString()) - ros_msg.annotations[-1].key = _item - ros_msg.annotations[-1].value = proto.annotations[_item] - ros_msg.checksum_type.value = proto.checksum_type - ros_msg.checksum_num_bytes = proto.checksum_num_bytes - - -def convert_bosdyn_msgs_file_format_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.FileFormatDescriptor", proto: "bosdyn.api.bddf_pb2.FileFormatDescriptor") -> None: - proto.Clear() - if ros_msg.version_is_set: - convert_bosdyn_msgs_file_format_version_to_proto(ros_msg.version, proto.version) - for _item in ros_msg.annotations: - proto.annotations[_item.key] = _item.value - proto.checksum_type = ros_msg.checksum_type.value - proto.checksum_num_bytes = ros_msg.checksum_num_bytes - - -def convert_proto_to_bosdyn_msgs_file_format_version(proto: "bosdyn.api.bddf_pb2.FileFormatVersion", ros_msg: "bosdyn_msgs.msgs.FileFormatVersion") -> None: - ros_msg.major_version = proto.major_version - ros_msg.minor_version = proto.minor_version - ros_msg.patch_level = proto.patch_level - - -def convert_bosdyn_msgs_file_format_version_to_proto(ros_msg: "bosdyn_msgs.msgs.FileFormatVersion", proto: "bosdyn.api.bddf_pb2.FileFormatVersion") -> None: - proto.Clear() - proto.major_version = ros_msg.major_version - proto.minor_version = ros_msg.minor_version - proto.patch_level = ros_msg.patch_level - - -def convert_proto_to_bosdyn_msgs_series_descriptor_one_of_data_type(proto: "bosdyn.api.bddf_pb2.SeriesDescriptor.DataType", ros_msg: "bosdyn_msgs.msgs.SeriesDescriptorOneOfDataType") -> None: - if proto.HasField("message_type"): - ros_msg.data_type_choice = ros_msg.DATATYPE_MESSAGE_TYPE_SET - convert_proto_to_bosdyn_msgs_message_type_descriptor(proto.message_type, ros_msg.message_type) - if proto.HasField("pod_type"): - ros_msg.data_type_choice = ros_msg.DATATYPE_POD_TYPE_SET - convert_proto_to_bosdyn_msgs_pod_type_descriptor(proto.pod_type, ros_msg.pod_type) - if proto.HasField("struct_type"): - ros_msg.data_type_choice = ros_msg.DATATYPE_STRUCT_TYPE_SET - convert_proto_to_bosdyn_msgs_struct_type_descriptor(proto.struct_type, ros_msg.struct_type) - - -def convert_bosdyn_msgs_series_descriptor_one_of_data_type_to_proto(ros_msg: "bosdyn_msgs.msgs.SeriesDescriptorOneOfDataType", proto: "bosdyn.api.bddf_pb2.SeriesDescriptor.DataType") -> None: - proto.ClearField("DataType") - if ros_msg.data_type_choice == ros_msg.DATATYPE_MESSAGE_TYPE_SET: - convert_bosdyn_msgs_message_type_descriptor_to_proto(ros_msg.message_type, proto.message_type) - if ros_msg.data_type_choice == ros_msg.DATATYPE_POD_TYPE_SET: - convert_bosdyn_msgs_pod_type_descriptor_to_proto(ros_msg.pod_type, proto.pod_type) - if ros_msg.data_type_choice == ros_msg.DATATYPE_STRUCT_TYPE_SET: - convert_bosdyn_msgs_struct_type_descriptor_to_proto(ros_msg.struct_type, proto.struct_type) - - -def convert_proto_to_bosdyn_msgs_series_descriptor(proto: "bosdyn.api.bddf_pb2.SeriesDescriptor", ros_msg: "bosdyn_msgs.msgs.SeriesDescriptor") -> None: - ros_msg.series_index = proto.series_index - convert_proto_to_bosdyn_msgs_series_identifier(proto.series_identifier, ros_msg.series_identifier) - ros_msg.series_identifier_is_set = proto.HasField("series_identifier") - ros_msg.identifier_hash = proto.identifier_hash - convert_proto_to_bosdyn_msgs_series_descriptor_one_of_data_type(proto, ros_msg.data_type) - from bosdyn_msgs.msg import KeyStringValueString - ros_msg.annotations = [] - for _item in proto.annotations: - ros_msg.annotations.append(KeyStringValueString()) - ros_msg.annotations[-1].key = _item - ros_msg.annotations[-1].value = proto.annotations[_item] - ros_msg.additional_index_names = [] - for _item in proto.additional_index_names: - ros_msg.additional_index_names.append(_item) - ros_msg.description = proto.description - - -def convert_bosdyn_msgs_series_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.SeriesDescriptor", proto: "bosdyn.api.bddf_pb2.SeriesDescriptor") -> None: - proto.Clear() - proto.series_index = ros_msg.series_index - if ros_msg.series_identifier_is_set: - convert_bosdyn_msgs_series_identifier_to_proto(ros_msg.series_identifier, proto.series_identifier) - proto.identifier_hash = ros_msg.identifier_hash - convert_bosdyn_msgs_series_descriptor_one_of_data_type_to_proto(ros_msg.data_type, proto) - for _item in ros_msg.annotations: - proto.annotations[_item.key] = _item.value - del proto.additional_index_names[:] - for _item in ros_msg.additional_index_names: - proto.additional_index_names.append(_item) - proto.description = ros_msg.description - - -def convert_proto_to_bosdyn_msgs_message_type_descriptor(proto: "bosdyn.api.bddf_pb2.MessageTypeDescriptor", ros_msg: "bosdyn_msgs.msgs.MessageTypeDescriptor") -> None: - ros_msg.content_type = proto.content_type - ros_msg.type_name = proto.type_name - ros_msg.is_metadata = proto.is_metadata - - -def convert_bosdyn_msgs_message_type_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.MessageTypeDescriptor", proto: "bosdyn.api.bddf_pb2.MessageTypeDescriptor") -> None: - proto.Clear() - proto.content_type = ros_msg.content_type - proto.type_name = ros_msg.type_name - proto.is_metadata = ros_msg.is_metadata - - -def convert_proto_to_bosdyn_msgs_pod_type_descriptor(proto: "bosdyn.api.bddf_pb2.PodTypeDescriptor", ros_msg: "bosdyn_msgs.msgs.PodTypeDescriptor") -> None: - ros_msg.pod_type.value = proto.pod_type - ros_msg.dimension = [] - for _item in proto.dimension: - ros_msg.dimension.append(_item) - - -def convert_bosdyn_msgs_pod_type_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.PodTypeDescriptor", proto: "bosdyn.api.bddf_pb2.PodTypeDescriptor") -> None: - proto.Clear() - proto.pod_type = ros_msg.pod_type.value - del proto.dimension[:] - for _item in ros_msg.dimension: - proto.dimension.append(_item) - - -def convert_proto_to_bosdyn_msgs_struct_type_descriptor(proto: "bosdyn.api.bddf_pb2.StructTypeDescriptor", ros_msg: "bosdyn_msgs.msgs.StructTypeDescriptor") -> None: - from bosdyn_msgs.msg import KeyStringValueUint64 - ros_msg.key_to_series_identifier_hash = [] - for _item in proto.key_to_series_identifier_hash: - ros_msg.key_to_series_identifier_hash.append(KeyStringValueUint64()) - ros_msg.key_to_series_identifier_hash[-1].key = _item - ros_msg.key_to_series_identifier_hash[-1].value = proto.key_to_series_identifier_hash[_item] - - -def convert_bosdyn_msgs_struct_type_descriptor_to_proto(ros_msg: "bosdyn_msgs.msgs.StructTypeDescriptor", proto: "bosdyn.api.bddf_pb2.StructTypeDescriptor") -> None: - proto.Clear() - for _item in ros_msg.key_to_series_identifier_hash: - proto.key_to_series_identifier_hash[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_pod_type_enum(proto: "bosdyn.api.bddf_pb2.PodTypeEnum", ros_msg: "bosdyn_msgs.msgs.PodTypeEnum") -> None: - pass - - -def convert_bosdyn_msgs_pod_type_enum_to_proto(ros_msg: "bosdyn_msgs.msgs.PodTypeEnum", proto: "bosdyn.api.bddf_pb2.PodTypeEnum") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_file_index(proto: "bosdyn.api.bddf_pb2.FileIndex", ros_msg: "bosdyn_msgs.msgs.FileIndex") -> None: - from bosdyn_msgs.msg import SeriesIdentifier - ros_msg.series_identifiers = [] - for _item in proto.series_identifiers: - ros_msg.series_identifiers.append(SeriesIdentifier()) - convert_proto_to_bosdyn_msgs_series_identifier(_item, ros_msg.series_identifiers[-1]) - ros_msg.series_block_index_offsets = [] - for _item in proto.series_block_index_offsets: - ros_msg.series_block_index_offsets.append(_item) - ros_msg.series_identifier_hashes = [] - for _item in proto.series_identifier_hashes: - ros_msg.series_identifier_hashes.append(_item) - - -def convert_bosdyn_msgs_file_index_to_proto(ros_msg: "bosdyn_msgs.msgs.FileIndex", proto: "bosdyn.api.bddf_pb2.FileIndex") -> None: - proto.Clear() - del proto.series_identifiers[:] - for _item in ros_msg.series_identifiers: - convert_bosdyn_msgs_series_identifier_to_proto(_item, proto.series_identifiers.add()) - del proto.series_block_index_offsets[:] - for _item in ros_msg.series_block_index_offsets: - proto.series_block_index_offsets.append(_item) - del proto.series_identifier_hashes[:] - for _item in ros_msg.series_identifier_hashes: - proto.series_identifier_hashes.append(_item) - - -def convert_proto_to_bosdyn_msgs_series_block_index_block_entry(proto: "bosdyn.api.bddf_pb2.SeriesBlockIndex.BlockEntry", ros_msg: "bosdyn_msgs.msgs.SeriesBlockIndexBlockEntry") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.file_offset = proto.file_offset - ros_msg.additional_indexes = [] - for _item in proto.additional_indexes: - ros_msg.additional_indexes.append(_item) - - -def convert_bosdyn_msgs_series_block_index_block_entry_to_proto(ros_msg: "bosdyn_msgs.msgs.SeriesBlockIndexBlockEntry", proto: "bosdyn.api.bddf_pb2.SeriesBlockIndex.BlockEntry") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.file_offset = ros_msg.file_offset - del proto.additional_indexes[:] - for _item in ros_msg.additional_indexes: - proto.additional_indexes.append(_item) - - -def convert_proto_to_bosdyn_msgs_series_block_index(proto: "bosdyn.api.bddf_pb2.SeriesBlockIndex", ros_msg: "bosdyn_msgs.msgs.SeriesBlockIndex") -> None: - ros_msg.series_index = proto.series_index - ros_msg.descriptor_file_offset = proto.descriptor_file_offset - from bosdyn_msgs.msg import SeriesBlockIndexBlockEntry - ros_msg.block_entries = [] - for _item in proto.block_entries: - ros_msg.block_entries.append(SeriesBlockIndexBlockEntry()) - convert_proto_to_bosdyn_msgs_series_block_index_block_entry(_item, ros_msg.block_entries[-1]) - ros_msg.total_bytes = proto.total_bytes - - -def convert_bosdyn_msgs_series_block_index_to_proto(ros_msg: "bosdyn_msgs.msgs.SeriesBlockIndex", proto: "bosdyn.api.bddf_pb2.SeriesBlockIndex") -> None: - proto.Clear() - proto.series_index = ros_msg.series_index - proto.descriptor_file_offset = ros_msg.descriptor_file_offset - del proto.block_entries[:] - for _item in ros_msg.block_entries: - convert_bosdyn_msgs_series_block_index_block_entry_to_proto(_item, proto.block_entries.add()) - proto.total_bytes = ros_msg.total_bytes - - -def convert_proto_to_bosdyn_msgs_series_identifier(proto: "bosdyn.api.bddf_pb2.SeriesIdentifier", ros_msg: "bosdyn_msgs.msgs.SeriesIdentifier") -> None: - ros_msg.series_type = proto.series_type - from bosdyn_msgs.msg import KeyStringValueString - ros_msg.spec = [] - for _item in proto.spec: - ros_msg.spec.append(KeyStringValueString()) - ros_msg.spec[-1].key = _item - ros_msg.spec[-1].value = proto.spec[_item] - - -def convert_bosdyn_msgs_series_identifier_to_proto(ros_msg: "bosdyn_msgs.msgs.SeriesIdentifier", proto: "bosdyn.api.bddf_pb2.SeriesIdentifier") -> None: - proto.Clear() - proto.series_type = ros_msg.series_type - for _item in ros_msg.spec: - proto.spec[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_data_acquisition_capability(proto: "bosdyn.api.data_acquisition_pb2.DataAcquisitionCapability", ros_msg: "bosdyn_msgs.msgs.DataAcquisitionCapability") -> None: - ros_msg.name = proto.name - ros_msg.description = proto.description - ros_msg.channel_name = proto.channel_name - ros_msg.service_name = proto.service_name - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_data_acquisition_capability_to_proto(ros_msg: "bosdyn_msgs.msgs.DataAcquisitionCapability", proto: "bosdyn.api.data_acquisition_pb2.DataAcquisitionCapability") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.description = ros_msg.description - proto.channel_name = ros_msg.channel_name - proto.service_name = ros_msg.service_name - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_image_acquisition_capability(proto: "bosdyn.api.data_acquisition_pb2.ImageAcquisitionCapability", ros_msg: "bosdyn_msgs.msgs.ImageAcquisitionCapability") -> None: - ros_msg.service_name = proto.service_name - from bosdyn_msgs.msg import ImageSource - ros_msg.image_sources = [] - for _item in proto.image_sources: - ros_msg.image_sources.append(ImageSource()) - convert_proto_to_bosdyn_msgs_image_source(_item, ros_msg.image_sources[-1]) - - -def convert_bosdyn_msgs_image_acquisition_capability_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageAcquisitionCapability", proto: "bosdyn.api.data_acquisition_pb2.ImageAcquisitionCapability") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - del proto.image_sources[:] - for _item in ros_msg.image_sources: - convert_bosdyn_msgs_image_source_to_proto(_item, proto.image_sources.add()) - - -def convert_proto_to_bosdyn_msgs_network_compute_capability(proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapability", ros_msg: "bosdyn_msgs.msgs.NetworkComputeCapability") -> None: - convert_proto_to_bosdyn_msgs_network_compute_server_configuration(proto.server_config, ros_msg.server_config) - ros_msg.server_config_is_set = proto.HasField("server_config") - convert_proto_to_bosdyn_msgs_available_models(proto.models, ros_msg.models) - ros_msg.models_is_set = proto.HasField("models") - - -def convert_bosdyn_msgs_network_compute_capability_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeCapability", proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapability") -> None: - proto.Clear() - if ros_msg.server_config_is_set: - convert_bosdyn_msgs_network_compute_server_configuration_to_proto(ros_msg.server_config, proto.server_config) - if ros_msg.models_is_set: - convert_bosdyn_msgs_available_models_to_proto(ros_msg.models, proto.models) - - -def convert_proto_to_bosdyn_msgs_acquisition_capability_list(proto: "bosdyn.api.data_acquisition_pb2.AcquisitionCapabilityList", ros_msg: "bosdyn_msgs.msgs.AcquisitionCapabilityList") -> None: - from bosdyn_msgs.msg import DataAcquisitionCapability - ros_msg.data_sources = [] - for _item in proto.data_sources: - ros_msg.data_sources.append(DataAcquisitionCapability()) - convert_proto_to_bosdyn_msgs_data_acquisition_capability(_item, ros_msg.data_sources[-1]) - from bosdyn_msgs.msg import ImageAcquisitionCapability - ros_msg.image_sources = [] - for _item in proto.image_sources: - ros_msg.image_sources.append(ImageAcquisitionCapability()) - convert_proto_to_bosdyn_msgs_image_acquisition_capability(_item, ros_msg.image_sources[-1]) - from bosdyn_msgs.msg import NetworkComputeCapability - ros_msg.network_compute_sources = [] - for _item in proto.network_compute_sources: - ros_msg.network_compute_sources.append(NetworkComputeCapability()) - convert_proto_to_bosdyn_msgs_network_compute_capability(_item, ros_msg.network_compute_sources[-1]) - - -def convert_bosdyn_msgs_acquisition_capability_list_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquisitionCapabilityList", proto: "bosdyn.api.data_acquisition_pb2.AcquisitionCapabilityList") -> None: - proto.Clear() - del proto.data_sources[:] - for _item in ros_msg.data_sources: - convert_bosdyn_msgs_data_acquisition_capability_to_proto(_item, proto.data_sources.add()) - del proto.image_sources[:] - for _item in ros_msg.image_sources: - convert_bosdyn_msgs_image_acquisition_capability_to_proto(_item, proto.image_sources.add()) - del proto.network_compute_sources[:] - for _item in ros_msg.network_compute_sources: - convert_bosdyn_msgs_network_compute_capability_to_proto(_item, proto.network_compute_sources.add()) - - -def convert_proto_to_bosdyn_msgs_capture_action_id(proto: "bosdyn.api.data_acquisition_pb2.CaptureActionId", ros_msg: "bosdyn_msgs.msgs.CaptureActionId") -> None: - ros_msg.action_name = proto.action_name - ros_msg.group_name = proto.group_name - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - - -def convert_bosdyn_msgs_capture_action_id_to_proto(ros_msg: "bosdyn_msgs.msgs.CaptureActionId", proto: "bosdyn.api.data_acquisition_pb2.CaptureActionId") -> None: - proto.Clear() - proto.action_name = ros_msg.action_name - proto.group_name = ros_msg.group_name - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - - -def convert_proto_to_bosdyn_msgs_data_identifier(proto: "bosdyn.api.data_acquisition_pb2.DataIdentifier", ros_msg: "bosdyn_msgs.msgs.DataIdentifier") -> None: - convert_proto_to_bosdyn_msgs_capture_action_id(proto.action_id, ros_msg.action_id) - ros_msg.action_id_is_set = proto.HasField("action_id") - ros_msg.channel = proto.channel - ros_msg.data_name = proto.data_name - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_data_identifier_to_proto(ros_msg: "bosdyn_msgs.msgs.DataIdentifier", proto: "bosdyn.api.data_acquisition_pb2.DataIdentifier") -> None: - proto.Clear() - if ros_msg.action_id_is_set: - convert_bosdyn_msgs_capture_action_id_to_proto(ros_msg.action_id, proto.action_id) - proto.channel = ros_msg.channel - proto.data_name = ros_msg.data_name - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_metadata(proto: "bosdyn.api.data_acquisition_pb2.Metadata", ros_msg: "bosdyn_msgs.msgs.Metadata") -> None: - pass - - -def convert_bosdyn_msgs_metadata_to_proto(ros_msg: "bosdyn_msgs.msgs.Metadata", proto: "bosdyn.api.data_acquisition_pb2.Metadata") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_associated_metadata(proto: "bosdyn.api.data_acquisition_pb2.AssociatedMetadata", ros_msg: "bosdyn_msgs.msgs.AssociatedMetadata") -> None: - convert_proto_to_bosdyn_msgs_data_identifier(proto.reference_id, ros_msg.reference_id) - ros_msg.reference_id_is_set = proto.HasField("reference_id") - convert_proto_to_bosdyn_msgs_metadata(proto.metadata, ros_msg.metadata) - ros_msg.metadata_is_set = proto.HasField("metadata") - - -def convert_bosdyn_msgs_associated_metadata_to_proto(ros_msg: "bosdyn_msgs.msgs.AssociatedMetadata", proto: "bosdyn.api.data_acquisition_pb2.AssociatedMetadata") -> None: - proto.Clear() - if ros_msg.reference_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.reference_id, proto.reference_id) - if ros_msg.metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.metadata, proto.metadata) - - -def convert_proto_to_bosdyn_msgs_associated_alert_data(proto: "bosdyn.api.data_acquisition_pb2.AssociatedAlertData", ros_msg: "bosdyn_msgs.msgs.AssociatedAlertData") -> None: - convert_proto_to_bosdyn_msgs_data_identifier(proto.reference_id, ros_msg.reference_id) - ros_msg.reference_id_is_set = proto.HasField("reference_id") - convert_proto_to_bosdyn_msgs_alert_data(proto.alert_data, ros_msg.alert_data) - ros_msg.alert_data_is_set = proto.HasField("alert_data") - - -def convert_bosdyn_msgs_associated_alert_data_to_proto(ros_msg: "bosdyn_msgs.msgs.AssociatedAlertData", proto: "bosdyn.api.data_acquisition_pb2.AssociatedAlertData") -> None: - proto.Clear() - if ros_msg.reference_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.reference_id, proto.reference_id) - if ros_msg.alert_data_is_set: - convert_bosdyn_msgs_alert_data_to_proto(ros_msg.alert_data, proto.alert_data) - - -def convert_proto_to_bosdyn_msgs_image_source_capture(proto: "bosdyn.api.data_acquisition_pb2.ImageSourceCapture", ros_msg: "bosdyn_msgs.msgs.ImageSourceCapture") -> None: - ros_msg.image_service = proto.image_service - convert_proto_to_bosdyn_msgs_image_request(proto.image_request, ros_msg.image_request) - ros_msg.image_request_is_set = proto.HasField("image_request") - - -def convert_bosdyn_msgs_image_source_capture_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourceCapture", proto: "bosdyn.api.data_acquisition_pb2.ImageSourceCapture") -> None: - proto.Clear() - proto.image_service = ros_msg.image_service - if ros_msg.image_request_is_set: - convert_bosdyn_msgs_image_request_to_proto(ros_msg.image_request, proto.image_request) - - -def convert_proto_to_bosdyn_msgs_data_capture(proto: "bosdyn.api.data_acquisition_pb2.DataCapture", ros_msg: "bosdyn_msgs.msgs.DataCapture") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_data_capture_to_proto(ros_msg: "bosdyn_msgs.msgs.DataCapture", proto: "bosdyn.api.data_acquisition_pb2.DataCapture") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_network_compute_capture_one_of_input(proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapture", ros_msg: "bosdyn_msgs.msgs.NetworkComputeCaptureOneOfInput") -> None: - if proto.HasField("input_data_bridge"): - ros_msg.input_choice = ros_msg.INPUT_INPUT_DATA_BRIDGE_SET - convert_proto_to_bosdyn_msgs_network_compute_input_data_bridge(proto.input_data_bridge, ros_msg.input_data_bridge) - - -def convert_bosdyn_msgs_network_compute_capture_one_of_input_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeCaptureOneOfInput", proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapture") -> None: - proto.ClearField("input") - if ros_msg.input_choice == ros_msg.INPUT_INPUT_DATA_BRIDGE_SET: - convert_bosdyn_msgs_network_compute_input_data_bridge_to_proto(ros_msg.input_data_bridge, proto.input_data_bridge) - - -def convert_proto_to_bosdyn_msgs_network_compute_capture(proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapture", ros_msg: "bosdyn_msgs.msgs.NetworkComputeCapture") -> None: - convert_proto_to_bosdyn_msgs_network_compute_capture_one_of_input(proto, ros_msg.input) - convert_proto_to_bosdyn_msgs_network_compute_server_configuration(proto.server_config, ros_msg.server_config) - ros_msg.server_config_is_set = proto.HasField("server_config") - - -def convert_bosdyn_msgs_network_compute_capture_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeCapture", proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeCapture") -> None: - proto.Clear() - convert_bosdyn_msgs_network_compute_capture_one_of_input_to_proto(ros_msg.input, proto) - if ros_msg.server_config_is_set: - convert_bosdyn_msgs_network_compute_server_configuration_to_proto(ros_msg.server_config, proto.server_config) - - -def convert_proto_to_bosdyn_msgs_acquisition_request_list(proto: "bosdyn.api.data_acquisition_pb2.AcquisitionRequestList", ros_msg: "bosdyn_msgs.msgs.AcquisitionRequestList") -> None: - from bosdyn_msgs.msg import ImageSourceCapture - ros_msg.image_captures = [] - for _item in proto.image_captures: - ros_msg.image_captures.append(ImageSourceCapture()) - convert_proto_to_bosdyn_msgs_image_source_capture(_item, ros_msg.image_captures[-1]) - from bosdyn_msgs.msg import DataCapture - ros_msg.data_captures = [] - for _item in proto.data_captures: - ros_msg.data_captures.append(DataCapture()) - convert_proto_to_bosdyn_msgs_data_capture(_item, ros_msg.data_captures[-1]) - from bosdyn_msgs.msg import NetworkComputeCapture - ros_msg.network_compute_captures = [] - for _item in proto.network_compute_captures: - ros_msg.network_compute_captures.append(NetworkComputeCapture()) - convert_proto_to_bosdyn_msgs_network_compute_capture(_item, ros_msg.network_compute_captures[-1]) - - -def convert_bosdyn_msgs_acquisition_request_list_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquisitionRequestList", proto: "bosdyn.api.data_acquisition_pb2.AcquisitionRequestList") -> None: - proto.Clear() - del proto.image_captures[:] - for _item in ros_msg.image_captures: - convert_bosdyn_msgs_image_source_capture_to_proto(_item, proto.image_captures.add()) - del proto.data_captures[:] - for _item in ros_msg.data_captures: - convert_bosdyn_msgs_data_capture_to_proto(_item, proto.data_captures.add()) - del proto.network_compute_captures[:] - for _item in ros_msg.network_compute_captures: - convert_bosdyn_msgs_network_compute_capture_to_proto(_item, proto.network_compute_captures.add()) - - -def convert_proto_to_bosdyn_msgs_data_error(proto: "bosdyn.api.data_acquisition_pb2.DataError", ros_msg: "bosdyn_msgs.msgs.DataError") -> None: - convert_proto_to_bosdyn_msgs_data_identifier(proto.data_id, ros_msg.data_id) - ros_msg.data_id_is_set = proto.HasField("data_id") - ros_msg.error_message = proto.error_message - - -def convert_bosdyn_msgs_data_error_to_proto(ros_msg: "bosdyn_msgs.msgs.DataError", proto: "bosdyn.api.data_acquisition_pb2.DataError") -> None: - proto.Clear() - if ros_msg.data_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.data_id, proto.data_id) - proto.error_message = ros_msg.error_message - - -def convert_proto_to_bosdyn_msgs_plugin_service_error_error_code(proto: "bosdyn.api.data_acquisition_pb2.PluginServiceError.ErrorCode", ros_msg: "bosdyn_msgs.msgs.PluginServiceErrorErrorCode") -> None: - pass - - -def convert_bosdyn_msgs_plugin_service_error_error_code_to_proto(ros_msg: "bosdyn_msgs.msgs.PluginServiceErrorErrorCode", proto: "bosdyn.api.data_acquisition_pb2.PluginServiceError.ErrorCode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_plugin_service_error(proto: "bosdyn.api.data_acquisition_pb2.PluginServiceError", ros_msg: "bosdyn_msgs.msgs.PluginServiceError") -> None: - ros_msg.service_name = proto.service_name - ros_msg.error.value = proto.error - ros_msg.message = proto.message - - -def convert_bosdyn_msgs_plugin_service_error_to_proto(ros_msg: "bosdyn_msgs.msgs.PluginServiceError", proto: "bosdyn.api.data_acquisition_pb2.PluginServiceError") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.error = ros_msg.error.value - proto.message = ros_msg.message - - -def convert_proto_to_bosdyn_msgs_network_compute_error_error_code(proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeError.ErrorCode", ros_msg: "bosdyn_msgs.msgs.NetworkComputeErrorErrorCode") -> None: - pass - - -def convert_bosdyn_msgs_network_compute_error_error_code_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeErrorErrorCode", proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeError.ErrorCode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_network_compute_error(proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeError", ros_msg: "bosdyn_msgs.msgs.NetworkComputeError") -> None: - ros_msg.service_name = proto.service_name - ros_msg.error.value = proto.error - ros_msg.network_compute_status.value = proto.network_compute_status - ros_msg.message = proto.message - - -def convert_bosdyn_msgs_network_compute_error_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeError", proto: "bosdyn.api.data_acquisition_pb2.NetworkComputeError") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.error = ros_msg.error.value - proto.network_compute_status = ros_msg.network_compute_status.value - proto.message = ros_msg.message - - -def convert_proto_to_bosdyn_msgs_acquire_data_request(proto: "bosdyn.api.data_acquisition_pb2.AcquireDataRequest", ros_msg: "bosdyn_msgs.msgs.AcquireDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_capture_action_id(proto.action_id, ros_msg.action_id) - ros_msg.action_id_is_set = proto.HasField("action_id") - convert_proto_to_bosdyn_msgs_metadata(proto.metadata, ros_msg.metadata) - ros_msg.metadata_is_set = proto.HasField("metadata") - convert_proto_to_bosdyn_msgs_acquisition_request_list(proto.acquisition_requests, ros_msg.acquisition_requests) - ros_msg.acquisition_requests_is_set = proto.HasField("acquisition_requests") - convert_proto_to_builtin_interfaces_duration(proto.min_timeout, ros_msg.min_timeout) - ros_msg.min_timeout_is_set = proto.HasField("min_timeout") - - -def convert_bosdyn_msgs_acquire_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireDataRequest", proto: "bosdyn.api.data_acquisition_pb2.AcquireDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.action_id_is_set: - convert_bosdyn_msgs_capture_action_id_to_proto(ros_msg.action_id, proto.action_id) - if ros_msg.metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.metadata, proto.metadata) - if ros_msg.acquisition_requests_is_set: - convert_bosdyn_msgs_acquisition_request_list_to_proto(ros_msg.acquisition_requests, proto.acquisition_requests) - if ros_msg.min_timeout_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.min_timeout, proto.min_timeout) - - -def convert_proto_to_bosdyn_msgs_acquire_data_response_status(proto: "bosdyn.api.data_acquisition_pb2.AcquireDataResponse.Status", ros_msg: "bosdyn_msgs.msgs.AcquireDataResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_acquire_data_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireDataResponseStatus", proto: "bosdyn.api.data_acquisition_pb2.AcquireDataResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_acquire_data_response(proto: "bosdyn.api.data_acquisition_pb2.AcquireDataResponse", ros_msg: "bosdyn_msgs.msgs.AcquireDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.request_id = proto.request_id - - -def convert_bosdyn_msgs_acquire_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireDataResponse", proto: "bosdyn.api.data_acquisition_pb2.AcquireDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.request_id = ros_msg.request_id - - -def convert_proto_to_bosdyn_msgs_acquire_plugin_data_request(proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataRequest", ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_id = [] - for _item in proto.data_id: - ros_msg.data_id.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_id[-1]) - convert_proto_to_bosdyn_msgs_metadata(proto.metadata, ros_msg.metadata) - ros_msg.metadata_is_set = proto.HasField("metadata") - convert_proto_to_bosdyn_msgs_capture_action_id(proto.action_id, ros_msg.action_id) - ros_msg.action_id_is_set = proto.HasField("action_id") - convert_proto_to_bosdyn_msgs_acquisition_request_list(proto.acquisition_requests, ros_msg.acquisition_requests) - ros_msg.acquisition_requests_is_set = proto.HasField("acquisition_requests") - - -def convert_bosdyn_msgs_acquire_plugin_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataRequest", proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.data_id[:] - for _item in ros_msg.data_id: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_id.add()) - if ros_msg.metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.metadata, proto.metadata) - if ros_msg.action_id_is_set: - convert_bosdyn_msgs_capture_action_id_to_proto(ros_msg.action_id, proto.action_id) - if ros_msg.acquisition_requests_is_set: - convert_bosdyn_msgs_acquisition_request_list_to_proto(ros_msg.acquisition_requests, proto.acquisition_requests) - - -def convert_proto_to_bosdyn_msgs_acquire_plugin_data_response_status(proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataResponse.Status", ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_acquire_plugin_data_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataResponseStatus", proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_acquire_plugin_data_response(proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataResponse", ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.request_id = proto.request_id - convert_proto_to_builtin_interfaces_time(proto.timeout_deadline, ros_msg.timeout_deadline) - ros_msg.timeout_deadline_is_set = proto.HasField("timeout_deadline") - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - - -def convert_bosdyn_msgs_acquire_plugin_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquirePluginDataResponse", proto: "bosdyn.api.data_acquisition_pb2.AcquirePluginDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.request_id = ros_msg.request_id - if ros_msg.timeout_deadline_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timeout_deadline, proto.timeout_deadline) - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - - -def convert_proto_to_bosdyn_msgs_get_status_request(proto: "bosdyn.api.data_acquisition_pb2.GetStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.request_id = proto.request_id - - -def convert_bosdyn_msgs_get_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStatusRequest", proto: "bosdyn.api.data_acquisition_pb2.GetStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.request_id = ros_msg.request_id - - -def convert_proto_to_bosdyn_msgs_get_status_response_status(proto: "bosdyn.api.data_acquisition_pb2.GetStatusResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetStatusResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_status_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStatusResponseStatus", proto: "bosdyn.api.data_acquisition_pb2.GetStatusResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_status_response(proto: "bosdyn.api.data_acquisition_pb2.GetStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_saved = [] - for _item in proto.data_saved: - ros_msg.data_saved.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_saved[-1]) - from bosdyn_msgs.msg import DataError - ros_msg.data_errors = [] - for _item in proto.data_errors: - ros_msg.data_errors.append(DataError()) - convert_proto_to_bosdyn_msgs_data_error(_item, ros_msg.data_errors[-1]) - from bosdyn_msgs.msg import PluginServiceError - ros_msg.service_errors = [] - for _item in proto.service_errors: - ros_msg.service_errors.append(PluginServiceError()) - convert_proto_to_bosdyn_msgs_plugin_service_error(_item, ros_msg.service_errors[-1]) - from bosdyn_msgs.msg import NetworkComputeError - ros_msg.network_compute_errors = [] - for _item in proto.network_compute_errors: - ros_msg.network_compute_errors.append(NetworkComputeError()) - convert_proto_to_bosdyn_msgs_network_compute_error(_item, ros_msg.network_compute_errors[-1]) - - -def convert_bosdyn_msgs_get_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStatusResponse", proto: "bosdyn.api.data_acquisition_pb2.GetStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.data_saved[:] - for _item in ros_msg.data_saved: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_saved.add()) - del proto.data_errors[:] - for _item in ros_msg.data_errors: - convert_bosdyn_msgs_data_error_to_proto(_item, proto.data_errors.add()) - del proto.service_errors[:] - for _item in ros_msg.service_errors: - convert_bosdyn_msgs_plugin_service_error_to_proto(_item, proto.service_errors.add()) - del proto.network_compute_errors[:] - for _item in ros_msg.network_compute_errors: - convert_bosdyn_msgs_network_compute_error_to_proto(_item, proto.network_compute_errors.add()) - - -def convert_proto_to_bosdyn_msgs_get_service_info_request(proto: "bosdyn.api.data_acquisition_pb2.GetServiceInfoRequest", ros_msg: "bosdyn_msgs.msgs.GetServiceInfoRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_service_info_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetServiceInfoRequest", proto: "bosdyn.api.data_acquisition_pb2.GetServiceInfoRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_service_info_response(proto: "bosdyn.api.data_acquisition_pb2.GetServiceInfoResponse", ros_msg: "bosdyn_msgs.msgs.GetServiceInfoResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_acquisition_capability_list(proto.capabilities, ros_msg.capabilities) - ros_msg.capabilities_is_set = proto.HasField("capabilities") - - -def convert_bosdyn_msgs_get_service_info_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetServiceInfoResponse", proto: "bosdyn.api.data_acquisition_pb2.GetServiceInfoResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.capabilities_is_set: - convert_bosdyn_msgs_acquisition_capability_list_to_proto(ros_msg.capabilities, proto.capabilities) - - -def convert_proto_to_bosdyn_msgs_cancel_acquisition_request(proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionRequest", ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.request_id = proto.request_id - - -def convert_bosdyn_msgs_cancel_acquisition_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionRequest", proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.request_id = ros_msg.request_id - - -def convert_proto_to_bosdyn_msgs_cancel_acquisition_response_status(proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionResponse.Status", ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_cancel_acquisition_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionResponseStatus", proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_cancel_acquisition_response(proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionResponse", ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_cancel_acquisition_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CancelAcquisitionResponse", proto: "bosdyn.api.data_acquisition_pb2.CancelAcquisitionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_action_id_query(proto: "bosdyn.api.data_acquisition_store_pb2.ActionIdQuery", ros_msg: "bosdyn_msgs.msgs.ActionIdQuery") -> None: - from bosdyn_msgs.msg import CaptureActionId - ros_msg.action_ids = [] - for _item in proto.action_ids: - ros_msg.action_ids.append(CaptureActionId()) - convert_proto_to_bosdyn_msgs_capture_action_id(_item, ros_msg.action_ids[-1]) - - -def convert_bosdyn_msgs_action_id_query_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionIdQuery", proto: "bosdyn.api.data_acquisition_store_pb2.ActionIdQuery") -> None: - proto.Clear() - del proto.action_ids[:] - for _item in ros_msg.action_ids: - convert_bosdyn_msgs_capture_action_id_to_proto(_item, proto.action_ids.add()) - - -def convert_proto_to_bosdyn_msgs_time_range_query(proto: "bosdyn.api.data_acquisition_store_pb2.TimeRangeQuery", ros_msg: "bosdyn_msgs.msgs.TimeRangeQuery") -> None: - convert_proto_to_builtin_interfaces_time(proto.from_timestamp, ros_msg.from_timestamp) - ros_msg.from_timestamp_is_set = proto.HasField("from_timestamp") - convert_proto_to_builtin_interfaces_time(proto.to_timestamp, ros_msg.to_timestamp) - ros_msg.to_timestamp_is_set = proto.HasField("to_timestamp") - - -def convert_bosdyn_msgs_time_range_query_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeRangeQuery", proto: "bosdyn.api.data_acquisition_store_pb2.TimeRangeQuery") -> None: - proto.Clear() - if ros_msg.from_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.from_timestamp, proto.from_timestamp) - if ros_msg.to_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.to_timestamp, proto.to_timestamp) - - -def convert_proto_to_bosdyn_msgs_data_query_params_one_of_query(proto: "bosdyn.api.data_acquisition_store_pb2.DataQueryParams", ros_msg: "bosdyn_msgs.msgs.DataQueryParamsOneOfQuery") -> None: - if proto.HasField("time_range"): - ros_msg.query_choice = ros_msg.QUERY_TIME_RANGE_SET - convert_proto_to_bosdyn_msgs_time_range_query(proto.time_range, ros_msg.time_range) - if proto.HasField("action_ids"): - ros_msg.query_choice = ros_msg.QUERY_ACTION_IDS_SET - convert_proto_to_bosdyn_msgs_action_id_query(proto.action_ids, ros_msg.action_ids) - - -def convert_bosdyn_msgs_data_query_params_one_of_query_to_proto(ros_msg: "bosdyn_msgs.msgs.DataQueryParamsOneOfQuery", proto: "bosdyn.api.data_acquisition_store_pb2.DataQueryParams") -> None: - proto.ClearField("query") - if ros_msg.query_choice == ros_msg.QUERY_TIME_RANGE_SET: - convert_bosdyn_msgs_time_range_query_to_proto(ros_msg.time_range, proto.time_range) - if ros_msg.query_choice == ros_msg.QUERY_ACTION_IDS_SET: - convert_bosdyn_msgs_action_id_query_to_proto(ros_msg.action_ids, proto.action_ids) - - -def convert_proto_to_bosdyn_msgs_data_query_params(proto: "bosdyn.api.data_acquisition_store_pb2.DataQueryParams", ros_msg: "bosdyn_msgs.msgs.DataQueryParams") -> None: - convert_proto_to_bosdyn_msgs_data_query_params_one_of_query(proto, ros_msg.query) - - -def convert_bosdyn_msgs_data_query_params_to_proto(ros_msg: "bosdyn_msgs.msgs.DataQueryParams", proto: "bosdyn.api.data_acquisition_store_pb2.DataQueryParams") -> None: - proto.Clear() - convert_bosdyn_msgs_data_query_params_one_of_query_to_proto(ros_msg.query, proto) - - -def convert_proto_to_bosdyn_msgs_store_image_request(proto: "bosdyn.api.data_acquisition_store_pb2.StoreImageRequest", ros_msg: "bosdyn_msgs.msgs.StoreImageRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_image_capture(proto.image, ros_msg.image) - ros_msg.image_is_set = proto.HasField("image") - convert_proto_to_bosdyn_msgs_data_identifier(proto.data_id, ros_msg.data_id) - ros_msg.data_id_is_set = proto.HasField("data_id") - - -def convert_bosdyn_msgs_store_image_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreImageRequest", proto: "bosdyn.api.data_acquisition_store_pb2.StoreImageRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.image_is_set: - convert_bosdyn_msgs_image_capture_to_proto(ros_msg.image, proto.image) - if ros_msg.data_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.data_id, proto.data_id) - - -def convert_proto_to_bosdyn_msgs_store_image_response(proto: "bosdyn.api.data_acquisition_store_pb2.StoreImageResponse", ros_msg: "bosdyn_msgs.msgs.StoreImageResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_store_image_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreImageResponse", proto: "bosdyn.api.data_acquisition_store_pb2.StoreImageResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_store_metadata_request(proto: "bosdyn.api.data_acquisition_store_pb2.StoreMetadataRequest", ros_msg: "bosdyn_msgs.msgs.StoreMetadataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_associated_metadata(proto.metadata, ros_msg.metadata) - ros_msg.metadata_is_set = proto.HasField("metadata") - convert_proto_to_bosdyn_msgs_data_identifier(proto.data_id, ros_msg.data_id) - ros_msg.data_id_is_set = proto.HasField("data_id") - - -def convert_bosdyn_msgs_store_metadata_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreMetadataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.StoreMetadataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.metadata_is_set: - convert_bosdyn_msgs_associated_metadata_to_proto(ros_msg.metadata, proto.metadata) - if ros_msg.data_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.data_id, proto.data_id) - - -def convert_proto_to_bosdyn_msgs_store_metadata_response(proto: "bosdyn.api.data_acquisition_store_pb2.StoreMetadataResponse", ros_msg: "bosdyn_msgs.msgs.StoreMetadataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_store_metadata_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreMetadataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.StoreMetadataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_store_alert_data_request(proto: "bosdyn.api.data_acquisition_store_pb2.StoreAlertDataRequest", ros_msg: "bosdyn_msgs.msgs.StoreAlertDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_associated_alert_data(proto.alert_data, ros_msg.alert_data) - ros_msg.alert_data_is_set = proto.HasField("alert_data") - convert_proto_to_bosdyn_msgs_data_identifier(proto.data_id, ros_msg.data_id) - ros_msg.data_id_is_set = proto.HasField("data_id") - - -def convert_bosdyn_msgs_store_alert_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreAlertDataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.StoreAlertDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.alert_data_is_set: - convert_bosdyn_msgs_associated_alert_data_to_proto(ros_msg.alert_data, proto.alert_data) - if ros_msg.data_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.data_id, proto.data_id) - - -def convert_proto_to_bosdyn_msgs_store_alert_data_response(proto: "bosdyn.api.data_acquisition_store_pb2.StoreAlertDataResponse", ros_msg: "bosdyn_msgs.msgs.StoreAlertDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_store_alert_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreAlertDataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.StoreAlertDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_store_data_request(proto: "bosdyn.api.data_acquisition_store_pb2.StoreDataRequest", ros_msg: "bosdyn_msgs.msgs.StoreDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.data = proto.data - convert_proto_to_bosdyn_msgs_data_identifier(proto.data_id, ros_msg.data_id) - ros_msg.data_id_is_set = proto.HasField("data_id") - ros_msg.file_extension = proto.file_extension - - -def convert_bosdyn_msgs_store_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreDataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.StoreDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.data = ros_msg.data - if ros_msg.data_id_is_set: - convert_bosdyn_msgs_data_identifier_to_proto(ros_msg.data_id, proto.data_id) - proto.file_extension = ros_msg.file_extension - - -def convert_proto_to_bosdyn_msgs_store_data_response(proto: "bosdyn.api.data_acquisition_store_pb2.StoreDataResponse", ros_msg: "bosdyn_msgs.msgs.StoreDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_store_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreDataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.StoreDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_list_capture_actions_request(proto: "bosdyn.api.data_acquisition_store_pb2.ListCaptureActionsRequest", ros_msg: "bosdyn_msgs.msgs.ListCaptureActionsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query_params(proto.query, ros_msg.query) - ros_msg.query_is_set = proto.HasField("query") - - -def convert_bosdyn_msgs_list_capture_actions_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListCaptureActionsRequest", proto: "bosdyn.api.data_acquisition_store_pb2.ListCaptureActionsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.query_is_set: - convert_bosdyn_msgs_data_query_params_to_proto(ros_msg.query, proto.query) - - -def convert_proto_to_bosdyn_msgs_list_capture_actions_response(proto: "bosdyn.api.data_acquisition_store_pb2.ListCaptureActionsResponse", ros_msg: "bosdyn_msgs.msgs.ListCaptureActionsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import CaptureActionId - ros_msg.action_ids = [] - for _item in proto.action_ids: - ros_msg.action_ids.append(CaptureActionId()) - convert_proto_to_bosdyn_msgs_capture_action_id(_item, ros_msg.action_ids[-1]) - - -def convert_bosdyn_msgs_list_capture_actions_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListCaptureActionsResponse", proto: "bosdyn.api.data_acquisition_store_pb2.ListCaptureActionsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.action_ids[:] - for _item in ros_msg.action_ids: - convert_bosdyn_msgs_capture_action_id_to_proto(_item, proto.action_ids.add()) - - -def convert_proto_to_bosdyn_msgs_list_stored_images_request(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredImagesRequest", ros_msg: "bosdyn_msgs.msgs.ListStoredImagesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query_params(proto.query, ros_msg.query) - ros_msg.query_is_set = proto.HasField("query") - - -def convert_bosdyn_msgs_list_stored_images_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredImagesRequest", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredImagesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.query_is_set: - convert_bosdyn_msgs_data_query_params_to_proto(ros_msg.query, proto.query) - - -def convert_proto_to_bosdyn_msgs_list_stored_images_response(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredImagesResponse", ros_msg: "bosdyn_msgs.msgs.ListStoredImagesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_ids = [] - for _item in proto.data_ids: - ros_msg.data_ids.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_ids[-1]) - - -def convert_bosdyn_msgs_list_stored_images_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredImagesResponse", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredImagesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.data_ids[:] - for _item in ros_msg.data_ids: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_ids.add()) - - -def convert_proto_to_bosdyn_msgs_list_stored_metadata_request(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredMetadataRequest", ros_msg: "bosdyn_msgs.msgs.ListStoredMetadataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query_params(proto.query, ros_msg.query) - ros_msg.query_is_set = proto.HasField("query") - - -def convert_bosdyn_msgs_list_stored_metadata_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredMetadataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredMetadataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.query_is_set: - convert_bosdyn_msgs_data_query_params_to_proto(ros_msg.query, proto.query) - - -def convert_proto_to_bosdyn_msgs_list_stored_metadata_response(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredMetadataResponse", ros_msg: "bosdyn_msgs.msgs.ListStoredMetadataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_ids = [] - for _item in proto.data_ids: - ros_msg.data_ids.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_ids[-1]) - - -def convert_bosdyn_msgs_list_stored_metadata_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredMetadataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredMetadataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.data_ids[:] - for _item in ros_msg.data_ids: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_ids.add()) - - -def convert_proto_to_bosdyn_msgs_list_stored_alert_data_request(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredAlertDataRequest", ros_msg: "bosdyn_msgs.msgs.ListStoredAlertDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query_params(proto.query, ros_msg.query) - ros_msg.query_is_set = proto.HasField("query") - - -def convert_bosdyn_msgs_list_stored_alert_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredAlertDataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredAlertDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.query_is_set: - convert_bosdyn_msgs_data_query_params_to_proto(ros_msg.query, proto.query) - - -def convert_proto_to_bosdyn_msgs_list_stored_alert_data_response(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredAlertDataResponse", ros_msg: "bosdyn_msgs.msgs.ListStoredAlertDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_ids = [] - for _item in proto.data_ids: - ros_msg.data_ids.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_ids[-1]) - - -def convert_bosdyn_msgs_list_stored_alert_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredAlertDataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredAlertDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.data_ids[:] - for _item in ros_msg.data_ids: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_ids.add()) - - -def convert_proto_to_bosdyn_msgs_list_stored_data_request(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredDataRequest", ros_msg: "bosdyn_msgs.msgs.ListStoredDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query_params(proto.query, ros_msg.query) - ros_msg.query_is_set = proto.HasField("query") - - -def convert_bosdyn_msgs_list_stored_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredDataRequest", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.query_is_set: - convert_bosdyn_msgs_data_query_params_to_proto(ros_msg.query, proto.query) - - -def convert_proto_to_bosdyn_msgs_list_stored_data_response(proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredDataResponse", ros_msg: "bosdyn_msgs.msgs.ListStoredDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataIdentifier - ros_msg.data_ids = [] - for _item in proto.data_ids: - ros_msg.data_ids.append(DataIdentifier()) - convert_proto_to_bosdyn_msgs_data_identifier(_item, ros_msg.data_ids[-1]) - - -def convert_bosdyn_msgs_list_stored_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListStoredDataResponse", proto: "bosdyn.api.data_acquisition_store_pb2.ListStoredDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.data_ids[:] - for _item in ros_msg.data_ids: - convert_bosdyn_msgs_data_identifier_to_proto(_item, proto.data_ids.add()) - - -def convert_proto_to_bosdyn_msgs_record_text_messages_request(proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesRequest", ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import TextMessage - ros_msg.text_messages = [] - for _item in proto.text_messages: - ros_msg.text_messages.append(TextMessage()) - convert_proto_to_bosdyn_msgs_text_message(_item, ros_msg.text_messages[-1]) - - -def convert_bosdyn_msgs_record_text_messages_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesRequest", proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.text_messages[:] - for _item in ros_msg.text_messages: - convert_bosdyn_msgs_text_message_to_proto(_item, proto.text_messages.add()) - - -def convert_proto_to_bosdyn_msgs_record_operator_comments_request(proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsRequest", ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import OperatorComment - ros_msg.operator_comments = [] - for _item in proto.operator_comments: - ros_msg.operator_comments.append(OperatorComment()) - convert_proto_to_bosdyn_msgs_operator_comment(_item, ros_msg.operator_comments[-1]) - - -def convert_bosdyn_msgs_record_operator_comments_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsRequest", proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.operator_comments[:] - for _item in ros_msg.operator_comments: - convert_bosdyn_msgs_operator_comment_to_proto(_item, proto.operator_comments.add()) - - -def convert_proto_to_bosdyn_msgs_record_data_blobs_request(proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsRequest", ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import DataBlob - ros_msg.blob_data = [] - for _item in proto.blob_data: - ros_msg.blob_data.append(DataBlob()) - convert_proto_to_bosdyn_msgs_data_blob(_item, ros_msg.blob_data[-1]) - ros_msg.sync = proto.sync - - -def convert_bosdyn_msgs_record_data_blobs_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsRequest", proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.blob_data[:] - for _item in ros_msg.blob_data: - convert_bosdyn_msgs_data_blob_to_proto(_item, proto.blob_data.add()) - proto.sync = ros_msg.sync - - -def convert_proto_to_bosdyn_msgs_record_signal_ticks_request(proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksRequest", ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import SignalTick - ros_msg.tick_data = [] - for _item in proto.tick_data: - ros_msg.tick_data.append(SignalTick()) - convert_proto_to_bosdyn_msgs_signal_tick(_item, ros_msg.tick_data[-1]) - - -def convert_bosdyn_msgs_record_signal_ticks_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksRequest", proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.tick_data[:] - for _item in ros_msg.tick_data: - convert_bosdyn_msgs_signal_tick_to_proto(_item, proto.tick_data.add()) - - -def convert_proto_to_bosdyn_msgs_record_events_request(proto: "bosdyn.api.data_buffer_pb2.RecordEventsRequest", ros_msg: "bosdyn_msgs.msgs.RecordEventsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Event - ros_msg.events = [] - for _item in proto.events: - ros_msg.events.append(Event()) - convert_proto_to_bosdyn_msgs_event(_item, ros_msg.events[-1]) - - -def convert_bosdyn_msgs_record_events_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordEventsRequest", proto: "bosdyn.api.data_buffer_pb2.RecordEventsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.events[:] - for _item in ros_msg.events: - convert_bosdyn_msgs_event_to_proto(_item, proto.events.add()) - - -def convert_proto_to_bosdyn_msgs_text_message_level(proto: "bosdyn.api.data_buffer_pb2.TextMessage.Level", ros_msg: "bosdyn_msgs.msgs.TextMessageLevel") -> None: - pass - - -def convert_bosdyn_msgs_text_message_level_to_proto(ros_msg: "bosdyn_msgs.msgs.TextMessageLevel", proto: "bosdyn.api.data_buffer_pb2.TextMessage.Level") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_text_message(proto: "bosdyn.api.data_buffer_pb2.TextMessage", ros_msg: "bosdyn_msgs.msgs.TextMessage") -> None: - ros_msg.message = proto.message - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.source = proto.source - ros_msg.level.value = proto.level - ros_msg.tag = proto.tag - ros_msg.filename = proto.filename - ros_msg.line_number = proto.line_number - - -def convert_bosdyn_msgs_text_message_to_proto(ros_msg: "bosdyn_msgs.msgs.TextMessage", proto: "bosdyn.api.data_buffer_pb2.TextMessage") -> None: - proto.Clear() - proto.message = ros_msg.message - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.source = ros_msg.source - proto.level = ros_msg.level.value - proto.tag = ros_msg.tag - proto.filename = ros_msg.filename - proto.line_number = ros_msg.line_number - - -def convert_proto_to_bosdyn_msgs_operator_comment(proto: "bosdyn.api.data_buffer_pb2.OperatorComment", ros_msg: "bosdyn_msgs.msgs.OperatorComment") -> None: - ros_msg.message = proto.message - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - - -def convert_bosdyn_msgs_operator_comment_to_proto(ros_msg: "bosdyn_msgs.msgs.OperatorComment", proto: "bosdyn.api.data_buffer_pb2.OperatorComment") -> None: - proto.Clear() - proto.message = ros_msg.message - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - - -def convert_proto_to_bosdyn_msgs_data_blob(proto: "bosdyn.api.data_buffer_pb2.DataBlob", ros_msg: "bosdyn_msgs.msgs.DataBlob") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.channel = proto.channel - ros_msg.type_id = proto.type_id - ros_msg.data = proto.data - - -def convert_bosdyn_msgs_data_blob_to_proto(ros_msg: "bosdyn_msgs.msgs.DataBlob", proto: "bosdyn.api.data_buffer_pb2.DataBlob") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.channel = ros_msg.channel - proto.type_id = ros_msg.type_id - proto.data = ros_msg.data - - -def convert_proto_to_bosdyn_msgs_signal_schema_variable_type(proto: "bosdyn.api.data_buffer_pb2.SignalSchema.Variable.Type", ros_msg: "bosdyn_msgs.msgs.SignalSchemaVariableType") -> None: - pass - - -def convert_bosdyn_msgs_signal_schema_variable_type_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalSchemaVariableType", proto: "bosdyn.api.data_buffer_pb2.SignalSchema.Variable.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_signal_schema_variable(proto: "bosdyn.api.data_buffer_pb2.SignalSchema.Variable", ros_msg: "bosdyn_msgs.msgs.SignalSchemaVariable") -> None: - ros_msg.name = proto.name - ros_msg.type.value = proto.type - ros_msg.is_time = proto.is_time - - -def convert_bosdyn_msgs_signal_schema_variable_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalSchemaVariable", proto: "bosdyn.api.data_buffer_pb2.SignalSchema.Variable") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.type = ros_msg.type.value - proto.is_time = ros_msg.is_time - - -def convert_proto_to_bosdyn_msgs_signal_schema(proto: "bosdyn.api.data_buffer_pb2.SignalSchema", ros_msg: "bosdyn_msgs.msgs.SignalSchema") -> None: - from bosdyn_msgs.msg import SignalSchemaVariable - ros_msg.vars = [] - for _item in proto.vars: - ros_msg.vars.append(SignalSchemaVariable()) - convert_proto_to_bosdyn_msgs_signal_schema_variable(_item, ros_msg.vars[-1]) - ros_msg.schema_name = proto.schema_name - - -def convert_bosdyn_msgs_signal_schema_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalSchema", proto: "bosdyn.api.data_buffer_pb2.SignalSchema") -> None: - proto.Clear() - del proto.vars[:] - for _item in ros_msg.vars: - convert_bosdyn_msgs_signal_schema_variable_to_proto(_item, proto.vars.add()) - proto.schema_name = ros_msg.schema_name - - -def convert_proto_to_bosdyn_msgs_signal_schema_id(proto: "bosdyn.api.data_buffer_pb2.SignalSchemaId", ros_msg: "bosdyn_msgs.msgs.SignalSchemaId") -> None: - ros_msg.schema_id = proto.schema_id - convert_proto_to_bosdyn_msgs_signal_schema(proto.schema, ros_msg.schema) - ros_msg.schema_is_set = proto.HasField("schema") - - -def convert_bosdyn_msgs_signal_schema_id_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalSchemaId", proto: "bosdyn.api.data_buffer_pb2.SignalSchemaId") -> None: - proto.Clear() - proto.schema_id = ros_msg.schema_id - if ros_msg.schema_is_set: - convert_bosdyn_msgs_signal_schema_to_proto(ros_msg.schema, proto.schema) - - -def convert_proto_to_bosdyn_msgs_signal_tick_encoding(proto: "bosdyn.api.data_buffer_pb2.SignalTick.Encoding", ros_msg: "bosdyn_msgs.msgs.SignalTickEncoding") -> None: - pass - - -def convert_bosdyn_msgs_signal_tick_encoding_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalTickEncoding", proto: "bosdyn.api.data_buffer_pb2.SignalTick.Encoding") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_signal_tick(proto: "bosdyn.api.data_buffer_pb2.SignalTick", ros_msg: "bosdyn_msgs.msgs.SignalTick") -> None: - ros_msg.sequence_id = proto.sequence_id - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.source = proto.source - ros_msg.schema_id = proto.schema_id - ros_msg.encoding.value = proto.encoding - ros_msg.data = proto.data - - -def convert_bosdyn_msgs_signal_tick_to_proto(ros_msg: "bosdyn_msgs.msgs.SignalTick", proto: "bosdyn.api.data_buffer_pb2.SignalTick") -> None: - proto.Clear() - proto.sequence_id = ros_msg.sequence_id - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.source = ros_msg.source - proto.schema_id = ros_msg.schema_id - proto.encoding = ros_msg.encoding.value - proto.data = ros_msg.data - - -def convert_proto_to_bosdyn_msgs_event_level(proto: "bosdyn.api.data_buffer_pb2.Event.Level", ros_msg: "bosdyn_msgs.msgs.EventLevel") -> None: - pass - - -def convert_bosdyn_msgs_event_level_to_proto(ros_msg: "bosdyn_msgs.msgs.EventLevel", proto: "bosdyn.api.data_buffer_pb2.Event.Level") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_event_log_preserve_hint(proto: "bosdyn.api.data_buffer_pb2.Event.LogPreserveHint", ros_msg: "bosdyn_msgs.msgs.EventLogPreserveHint") -> None: - pass - - -def convert_bosdyn_msgs_event_log_preserve_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.EventLogPreserveHint", proto: "bosdyn.api.data_buffer_pb2.Event.LogPreserveHint") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_event(proto: "bosdyn.api.data_buffer_pb2.Event", ros_msg: "bosdyn_msgs.msgs.Event") -> None: - ros_msg.type = proto.type - ros_msg.description = proto.description - ros_msg.source = proto.source - ros_msg.id = proto.id - convert_proto_to_builtin_interfaces_time(proto.start_time, ros_msg.start_time) - ros_msg.start_time_is_set = proto.HasField("start_time") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.level.value = proto.level - from bosdyn_msgs.msg import Parameter - ros_msg.parameters = [] - for _item in proto.parameters: - ros_msg.parameters.append(Parameter()) - convert_proto_to_bosdyn_msgs_parameter(_item, ros_msg.parameters[-1]) - ros_msg.log_preserve_hint.value = proto.log_preserve_hint - - -def convert_bosdyn_msgs_event_to_proto(ros_msg: "bosdyn_msgs.msgs.Event", proto: "bosdyn.api.data_buffer_pb2.Event") -> None: - proto.Clear() - proto.type = ros_msg.type - proto.description = ros_msg.description - proto.source = ros_msg.source - proto.id = ros_msg.id - if ros_msg.start_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.start_time, proto.start_time) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.level = ros_msg.level.value - del proto.parameters[:] - for _item in ros_msg.parameters: - convert_bosdyn_msgs_parameter_to_proto(_item, proto.parameters.add()) - proto.log_preserve_hint = ros_msg.log_preserve_hint.value - - -def convert_proto_to_bosdyn_msgs_record_text_messages_response_error_type(proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse.Error.Type", ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponseErrorType") -> None: - pass - - -def convert_bosdyn_msgs_record_text_messages_response_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponseErrorType", proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse.Error.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_record_text_messages_response_error(proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse.Error", ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponseError") -> None: - ros_msg.type.value = proto.type - ros_msg.message = proto.message - ros_msg.index = proto.index - - -def convert_bosdyn_msgs_record_text_messages_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponseError", proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse.Error") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.message = ros_msg.message - proto.index = ros_msg.index - - -def convert_proto_to_bosdyn_msgs_record_text_messages_response(proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse", ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import RecordTextMessagesResponseError - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(RecordTextMessagesResponseError()) - convert_proto_to_bosdyn_msgs_record_text_messages_response_error(_item, ros_msg.errors[-1]) - - -def convert_bosdyn_msgs_record_text_messages_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordTextMessagesResponse", proto: "bosdyn.api.data_buffer_pb2.RecordTextMessagesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.errors[:] - for _item in ros_msg.errors: - convert_bosdyn_msgs_record_text_messages_response_error_to_proto(_item, proto.errors.add()) - - -def convert_proto_to_bosdyn_msgs_record_operator_comments_response_error_type(proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse.Error.Type", ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponseErrorType") -> None: - pass - - -def convert_bosdyn_msgs_record_operator_comments_response_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponseErrorType", proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse.Error.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_record_operator_comments_response_error(proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse.Error", ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponseError") -> None: - ros_msg.type.value = proto.type - ros_msg.message = proto.message - ros_msg.index = proto.index - - -def convert_bosdyn_msgs_record_operator_comments_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponseError", proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse.Error") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.message = ros_msg.message - proto.index = ros_msg.index - - -def convert_proto_to_bosdyn_msgs_record_operator_comments_response(proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse", ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import RecordOperatorCommentsResponseError - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(RecordOperatorCommentsResponseError()) - convert_proto_to_bosdyn_msgs_record_operator_comments_response_error(_item, ros_msg.errors[-1]) - - -def convert_bosdyn_msgs_record_operator_comments_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordOperatorCommentsResponse", proto: "bosdyn.api.data_buffer_pb2.RecordOperatorCommentsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.errors[:] - for _item in ros_msg.errors: - convert_bosdyn_msgs_record_operator_comments_response_error_to_proto(_item, proto.errors.add()) - - -def convert_proto_to_bosdyn_msgs_record_data_blobs_response_error_type(proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse.Error.Type", ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponseErrorType") -> None: - pass - - -def convert_bosdyn_msgs_record_data_blobs_response_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponseErrorType", proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse.Error.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_record_data_blobs_response_error(proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse.Error", ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponseError") -> None: - ros_msg.type.value = proto.type - ros_msg.message = proto.message - ros_msg.index = proto.index - - -def convert_bosdyn_msgs_record_data_blobs_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponseError", proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse.Error") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.message = ros_msg.message - proto.index = ros_msg.index - - -def convert_proto_to_bosdyn_msgs_record_data_blobs_response(proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse", ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import RecordDataBlobsResponseError - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(RecordDataBlobsResponseError()) - convert_proto_to_bosdyn_msgs_record_data_blobs_response_error(_item, ros_msg.errors[-1]) - - -def convert_bosdyn_msgs_record_data_blobs_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordDataBlobsResponse", proto: "bosdyn.api.data_buffer_pb2.RecordDataBlobsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.errors[:] - for _item in ros_msg.errors: - convert_bosdyn_msgs_record_data_blobs_response_error_to_proto(_item, proto.errors.add()) - - -def convert_proto_to_bosdyn_msgs_record_signal_ticks_response_error_type(proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse.Error.Type", ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponseErrorType") -> None: - pass - - -def convert_bosdyn_msgs_record_signal_ticks_response_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponseErrorType", proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse.Error.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_record_signal_ticks_response_error(proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse.Error", ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponseError") -> None: - ros_msg.type.value = proto.type - ros_msg.message = proto.message - ros_msg.index = proto.index - - -def convert_bosdyn_msgs_record_signal_ticks_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponseError", proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse.Error") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.message = ros_msg.message - proto.index = ros_msg.index - - -def convert_proto_to_bosdyn_msgs_record_signal_ticks_response(proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse", ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import RecordSignalTicksResponseError - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(RecordSignalTicksResponseError()) - convert_proto_to_bosdyn_msgs_record_signal_ticks_response_error(_item, ros_msg.errors[-1]) - - -def convert_bosdyn_msgs_record_signal_ticks_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordSignalTicksResponse", proto: "bosdyn.api.data_buffer_pb2.RecordSignalTicksResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.errors[:] - for _item in ros_msg.errors: - convert_bosdyn_msgs_record_signal_ticks_response_error_to_proto(_item, proto.errors.add()) - - -def convert_proto_to_bosdyn_msgs_record_events_response_error_type(proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse.Error.Type", ros_msg: "bosdyn_msgs.msgs.RecordEventsResponseErrorType") -> None: - pass - - -def convert_bosdyn_msgs_record_events_response_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordEventsResponseErrorType", proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse.Error.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_record_events_response_error(proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse.Error", ros_msg: "bosdyn_msgs.msgs.RecordEventsResponseError") -> None: - ros_msg.type.value = proto.type - ros_msg.message = proto.message - ros_msg.index = proto.index - - -def convert_bosdyn_msgs_record_events_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordEventsResponseError", proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse.Error") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.message = ros_msg.message - proto.index = ros_msg.index - - -def convert_proto_to_bosdyn_msgs_record_events_response(proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse", ros_msg: "bosdyn_msgs.msgs.RecordEventsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import RecordEventsResponseError - ros_msg.errors = [] - for _item in proto.errors: - ros_msg.errors.append(RecordEventsResponseError()) - convert_proto_to_bosdyn_msgs_record_events_response_error(_item, ros_msg.errors[-1]) - - -def convert_bosdyn_msgs_record_events_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordEventsResponse", proto: "bosdyn.api.data_buffer_pb2.RecordEventsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.errors[:] - for _item in ros_msg.errors: - convert_bosdyn_msgs_record_events_response_error_to_proto(_item, proto.errors.add()) - - -def convert_proto_to_bosdyn_msgs_register_signal_schema_request(proto: "bosdyn.api.data_buffer_pb2.RegisterSignalSchemaRequest", ros_msg: "bosdyn_msgs.msgs.RegisterSignalSchemaRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_signal_schema(proto.schema, ros_msg.schema) - ros_msg.schema_is_set = proto.HasField("schema") - - -def convert_bosdyn_msgs_register_signal_schema_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterSignalSchemaRequest", proto: "bosdyn.api.data_buffer_pb2.RegisterSignalSchemaRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.schema_is_set: - convert_bosdyn_msgs_signal_schema_to_proto(ros_msg.schema, proto.schema) - - -def convert_proto_to_bosdyn_msgs_register_signal_schema_response(proto: "bosdyn.api.data_buffer_pb2.RegisterSignalSchemaResponse", ros_msg: "bosdyn_msgs.msgs.RegisterSignalSchemaResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.schema_id = proto.schema_id - - -def convert_bosdyn_msgs_register_signal_schema_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterSignalSchemaResponse", proto: "bosdyn.api.data_buffer_pb2.RegisterSignalSchemaResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.schema_id = ros_msg.schema_id - - -def convert_proto_to_bosdyn_msgs_data_chunk(proto: "bosdyn.api.data_chunk_pb2.DataChunk", ros_msg: "bosdyn_msgs.msgs.DataChunk") -> None: - ros_msg.total_size = proto.total_size - ros_msg.data = proto.data - - -def convert_bosdyn_msgs_data_chunk_to_proto(ros_msg: "bosdyn_msgs.msgs.DataChunk", proto: "bosdyn.api.data_chunk_pb2.DataChunk") -> None: - proto.Clear() - proto.total_size = ros_msg.total_size - proto.data = ros_msg.data - - -def convert_proto_to_bosdyn_msgs_grpc_spec(proto: "bosdyn.api.data_index_pb2.GrpcSpec", ros_msg: "bosdyn_msgs.msgs.GrpcSpec") -> None: - ros_msg.service_name = proto.service_name - - -def convert_bosdyn_msgs_grpc_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.GrpcSpec", proto: "bosdyn.api.data_index_pb2.GrpcSpec") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - - -def convert_proto_to_bosdyn_msgs_blob_spec(proto: "bosdyn.api.data_index_pb2.BlobSpec", ros_msg: "bosdyn_msgs.msgs.BlobSpec") -> None: - ros_msg.source = proto.source - ros_msg.message_type = proto.message_type - ros_msg.channel = proto.channel - ros_msg.channel_glob = proto.channel_glob - - -def convert_bosdyn_msgs_blob_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.BlobSpec", proto: "bosdyn.api.data_index_pb2.BlobSpec") -> None: - proto.Clear() - proto.source = ros_msg.source - proto.message_type = ros_msg.message_type - proto.channel = ros_msg.channel - proto.channel_glob = ros_msg.channel_glob - - -def convert_proto_to_bosdyn_msgs_event_spec(proto: "bosdyn.api.data_index_pb2.EventSpec", ros_msg: "bosdyn_msgs.msgs.EventSpec") -> None: - ros_msg.source = proto.source - ros_msg.type = proto.type - ros_msg.level = proto.level.value - ros_msg.level_is_set = proto.HasField("level") - ros_msg.log_preserve_hint.value = proto.log_preserve_hint - - -def convert_bosdyn_msgs_event_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.EventSpec", proto: "bosdyn.api.data_index_pb2.EventSpec") -> None: - proto.Clear() - proto.source = ros_msg.source - proto.type = ros_msg.type - if ros_msg.level_is_set: - convert_int32_to_proto(ros_msg.level, proto.level) - proto.log_preserve_hint = ros_msg.log_preserve_hint.value - - -def convert_proto_to_bosdyn_msgs_page_info_page_format(proto: "bosdyn.api.data_index_pb2.PageInfo.PageFormat", ros_msg: "bosdyn_msgs.msgs.PageInfoPageFormat") -> None: - pass - - -def convert_bosdyn_msgs_page_info_page_format_to_proto(ros_msg: "bosdyn_msgs.msgs.PageInfoPageFormat", proto: "bosdyn.api.data_index_pb2.PageInfo.PageFormat") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_page_info_compression(proto: "bosdyn.api.data_index_pb2.PageInfo.Compression", ros_msg: "bosdyn_msgs.msgs.PageInfoCompression") -> None: - pass - - -def convert_bosdyn_msgs_page_info_compression_to_proto(ros_msg: "bosdyn_msgs.msgs.PageInfoCompression", proto: "bosdyn.api.data_index_pb2.PageInfo.Compression") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_page_info(proto: "bosdyn.api.data_index_pb2.PageInfo", ros_msg: "bosdyn_msgs.msgs.PageInfo") -> None: - ros_msg.id = proto.id - ros_msg.path = proto.path - ros_msg.source = proto.source - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - ros_msg.num_ticks = proto.num_ticks - ros_msg.total_bytes = proto.total_bytes - ros_msg.format.value = proto.format - ros_msg.compression.value = proto.compression - ros_msg.is_open = proto.is_open - ros_msg.is_downloaded = proto.is_downloaded - convert_proto_to_builtin_interfaces_time(proto.deleted_timestamp, ros_msg.deleted_timestamp) - ros_msg.deleted_timestamp_is_set = proto.HasField("deleted_timestamp") - convert_proto_to_builtin_interfaces_time(proto.download_started_timestamp, ros_msg.download_started_timestamp) - ros_msg.download_started_timestamp_is_set = proto.HasField("download_started_timestamp") - ros_msg.request_preserve = proto.request_preserve - - -def convert_bosdyn_msgs_page_info_to_proto(ros_msg: "bosdyn_msgs.msgs.PageInfo", proto: "bosdyn.api.data_index_pb2.PageInfo") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.path = ros_msg.path - proto.source = ros_msg.source - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - proto.num_ticks = ros_msg.num_ticks - proto.total_bytes = ros_msg.total_bytes - proto.format = ros_msg.format.value - proto.compression = ros_msg.compression.value - proto.is_open = ros_msg.is_open - proto.is_downloaded = ros_msg.is_downloaded - if ros_msg.deleted_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.deleted_timestamp, proto.deleted_timestamp) - if ros_msg.download_started_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.download_started_timestamp, proto.download_started_timestamp) - proto.request_preserve = ros_msg.request_preserve - - -def convert_proto_to_bosdyn_msgs_grpc_pages(proto: "bosdyn.api.data_index_pb2.GrpcPages", ros_msg: "bosdyn_msgs.msgs.GrpcPages") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - convert_proto_to_bosdyn_msgs_grpc_spec(proto.spec, ros_msg.spec) - ros_msg.spec_is_set = proto.HasField("spec") - from bosdyn_msgs.msg import PageInfo - ros_msg.pages = [] - for _item in proto.pages: - ros_msg.pages.append(PageInfo()) - convert_proto_to_bosdyn_msgs_page_info(_item, ros_msg.pages[-1]) - - -def convert_bosdyn_msgs_grpc_pages_to_proto(ros_msg: "bosdyn_msgs.msgs.GrpcPages", proto: "bosdyn.api.data_index_pb2.GrpcPages") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - if ros_msg.spec_is_set: - convert_bosdyn_msgs_grpc_spec_to_proto(ros_msg.spec, proto.spec) - del proto.pages[:] - for _item in ros_msg.pages: - convert_bosdyn_msgs_page_info_to_proto(_item, proto.pages.add()) - - -def convert_proto_to_bosdyn_msgs_blob_page(proto: "bosdyn.api.data_index_pb2.BlobPage", ros_msg: "bosdyn_msgs.msgs.BlobPage") -> None: - convert_proto_to_bosdyn_msgs_blob_spec(proto.spec, ros_msg.spec) - ros_msg.spec_is_set = proto.HasField("spec") - convert_proto_to_bosdyn_msgs_page_info(proto.page, ros_msg.page) - ros_msg.page_is_set = proto.HasField("page") - - -def convert_bosdyn_msgs_blob_page_to_proto(ros_msg: "bosdyn_msgs.msgs.BlobPage", proto: "bosdyn.api.data_index_pb2.BlobPage") -> None: - proto.Clear() - if ros_msg.spec_is_set: - convert_bosdyn_msgs_blob_spec_to_proto(ros_msg.spec, proto.spec) - if ros_msg.page_is_set: - convert_bosdyn_msgs_page_info_to_proto(ros_msg.page, proto.page) - - -def convert_proto_to_bosdyn_msgs_blob_pages(proto: "bosdyn.api.data_index_pb2.BlobPages", ros_msg: "bosdyn_msgs.msgs.BlobPages") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import BlobPage - ros_msg.pages = [] - for _item in proto.pages: - ros_msg.pages.append(BlobPage()) - convert_proto_to_bosdyn_msgs_blob_page(_item, ros_msg.pages[-1]) - - -def convert_bosdyn_msgs_blob_pages_to_proto(ros_msg: "bosdyn_msgs.msgs.BlobPages", proto: "bosdyn.api.data_index_pb2.BlobPages") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.pages[:] - for _item in ros_msg.pages: - convert_bosdyn_msgs_blob_page_to_proto(_item, proto.pages.add()) - - -def convert_proto_to_bosdyn_msgs_pages_and_timestamp(proto: "bosdyn.api.data_index_pb2.PagesAndTimestamp", ros_msg: "bosdyn_msgs.msgs.PagesAndTimestamp") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import PageInfo - ros_msg.pages = [] - for _item in proto.pages: - ros_msg.pages.append(PageInfo()) - convert_proto_to_bosdyn_msgs_page_info(_item, ros_msg.pages[-1]) - - -def convert_bosdyn_msgs_pages_and_timestamp_to_proto(ros_msg: "bosdyn_msgs.msgs.PagesAndTimestamp", proto: "bosdyn.api.data_index_pb2.PagesAndTimestamp") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.pages[:] - for _item in ros_msg.pages: - convert_bosdyn_msgs_page_info_to_proto(_item, proto.pages.add()) - - -def convert_proto_to_bosdyn_msgs_data_query(proto: "bosdyn.api.data_index_pb2.DataQuery", ros_msg: "bosdyn_msgs.msgs.DataQuery") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import BlobSpec - ros_msg.blobs = [] - for _item in proto.blobs: - ros_msg.blobs.append(BlobSpec()) - convert_proto_to_bosdyn_msgs_blob_spec(_item, ros_msg.blobs[-1]) - ros_msg.text_messages = proto.text_messages - ros_msg.events = proto.events - ros_msg.comments = proto.comments - - -def convert_bosdyn_msgs_data_query_to_proto(ros_msg: "bosdyn_msgs.msgs.DataQuery", proto: "bosdyn.api.data_index_pb2.DataQuery") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.blobs[:] - for _item in ros_msg.blobs: - convert_bosdyn_msgs_blob_spec_to_proto(_item, proto.blobs.add()) - proto.text_messages = ros_msg.text_messages - proto.events = ros_msg.events - proto.comments = ros_msg.comments - - -def convert_proto_to_bosdyn_msgs_data_index(proto: "bosdyn.api.data_index_pb2.DataIndex", ros_msg: "bosdyn_msgs.msgs.DataIndex") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import BlobPages - ros_msg.blobs = [] - for _item in proto.blobs: - ros_msg.blobs.append(BlobPages()) - convert_proto_to_bosdyn_msgs_blob_pages(_item, ros_msg.blobs[-1]) - convert_proto_to_bosdyn_msgs_pages_and_timestamp(proto.text_messages, ros_msg.text_messages) - ros_msg.text_messages_is_set = proto.HasField("text_messages") - convert_proto_to_bosdyn_msgs_pages_and_timestamp(proto.events, ros_msg.events) - ros_msg.events_is_set = proto.HasField("events") - convert_proto_to_bosdyn_msgs_pages_and_timestamp(proto.comments, ros_msg.comments) - ros_msg.comments_is_set = proto.HasField("comments") - - -def convert_bosdyn_msgs_data_index_to_proto(ros_msg: "bosdyn_msgs.msgs.DataIndex", proto: "bosdyn.api.data_index_pb2.DataIndex") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.blobs[:] - for _item in ros_msg.blobs: - convert_bosdyn_msgs_blob_pages_to_proto(_item, proto.blobs.add()) - if ros_msg.text_messages_is_set: - convert_bosdyn_msgs_pages_and_timestamp_to_proto(ros_msg.text_messages, proto.text_messages) - if ros_msg.events_is_set: - convert_bosdyn_msgs_pages_and_timestamp_to_proto(ros_msg.events, proto.events) - if ros_msg.comments_is_set: - convert_bosdyn_msgs_pages_and_timestamp_to_proto(ros_msg.comments, proto.comments) - - -def convert_proto_to_bosdyn_msgs_events_comments_spec(proto: "bosdyn.api.data_index_pb2.EventsCommentsSpec", ros_msg: "bosdyn_msgs.msgs.EventsCommentsSpec") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import EventSpec - ros_msg.events = [] - for _item in proto.events: - ros_msg.events.append(EventSpec()) - convert_proto_to_bosdyn_msgs_event_spec(_item, ros_msg.events[-1]) - ros_msg.comments = proto.comments - ros_msg.max_events = proto.max_events - ros_msg.max_comments = proto.max_comments - - -def convert_bosdyn_msgs_events_comments_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.EventsCommentsSpec", proto: "bosdyn.api.data_index_pb2.EventsCommentsSpec") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.events[:] - for _item in ros_msg.events: - convert_bosdyn_msgs_event_spec_to_proto(_item, proto.events.add()) - proto.comments = ros_msg.comments - proto.max_events = ros_msg.max_events - proto.max_comments = ros_msg.max_comments - - -def convert_proto_to_bosdyn_msgs_events_comments(proto: "bosdyn.api.data_index_pb2.EventsComments", ros_msg: "bosdyn_msgs.msgs.EventsComments") -> None: - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - from bosdyn_msgs.msg import Event - ros_msg.events = [] - for _item in proto.events: - ros_msg.events.append(Event()) - convert_proto_to_bosdyn_msgs_event(_item, ros_msg.events[-1]) - from bosdyn_msgs.msg import OperatorComment - ros_msg.operator_comments = [] - for _item in proto.operator_comments: - ros_msg.operator_comments.append(OperatorComment()) - convert_proto_to_bosdyn_msgs_operator_comment(_item, ros_msg.operator_comments[-1]) - ros_msg.events_limited = proto.events_limited - ros_msg.operator_comments_limited = proto.operator_comments_limited - - -def convert_bosdyn_msgs_events_comments_to_proto(ros_msg: "bosdyn_msgs.msgs.EventsComments", proto: "bosdyn.api.data_index_pb2.EventsComments") -> None: - proto.Clear() - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.events[:] - for _item in ros_msg.events: - convert_bosdyn_msgs_event_to_proto(_item, proto.events.add()) - del proto.operator_comments[:] - for _item in ros_msg.operator_comments: - convert_bosdyn_msgs_operator_comment_to_proto(_item, proto.operator_comments.add()) - proto.events_limited = ros_msg.events_limited - proto.operator_comments_limited = ros_msg.operator_comments_limited - - -def convert_proto_to_bosdyn_msgs_data_buffer_status(proto: "bosdyn.api.data_index_pb2.DataBufferStatus", ros_msg: "bosdyn_msgs.msgs.DataBufferStatus") -> None: - ros_msg.num_data_buffer_pages = proto.num_data_buffer_pages - ros_msg.data_buffer_total_bytes = proto.data_buffer_total_bytes - ros_msg.num_comments = proto.num_comments - ros_msg.num_events = proto.num_events - from bosdyn_msgs.msg import BlobSpec - ros_msg.blob_specs = [] - for _item in proto.blob_specs: - ros_msg.blob_specs.append(BlobSpec()) - convert_proto_to_bosdyn_msgs_blob_spec(_item, ros_msg.blob_specs[-1]) - - -def convert_bosdyn_msgs_data_buffer_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DataBufferStatus", proto: "bosdyn.api.data_index_pb2.DataBufferStatus") -> None: - proto.Clear() - proto.num_data_buffer_pages = ros_msg.num_data_buffer_pages - proto.data_buffer_total_bytes = ros_msg.data_buffer_total_bytes - proto.num_comments = ros_msg.num_comments - proto.num_events = ros_msg.num_events - del proto.blob_specs[:] - for _item in ros_msg.blob_specs: - convert_bosdyn_msgs_blob_spec_to_proto(_item, proto.blob_specs.add()) - - -def convert_proto_to_bosdyn_msgs_get_data_index_response(proto: "bosdyn.api.data_index_pb2.GetDataIndexResponse", ros_msg: "bosdyn_msgs.msgs.GetDataIndexResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_index(proto.data_index, ros_msg.data_index) - ros_msg.data_index_is_set = proto.HasField("data_index") - - -def convert_bosdyn_msgs_get_data_index_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataIndexResponse", proto: "bosdyn.api.data_index_pb2.GetDataIndexResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.data_index_is_set: - convert_bosdyn_msgs_data_index_to_proto(ros_msg.data_index, proto.data_index) - - -def convert_proto_to_bosdyn_msgs_get_data_index_request(proto: "bosdyn.api.data_index_pb2.GetDataIndexRequest", ros_msg: "bosdyn_msgs.msgs.GetDataIndexRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_query(proto.data_query, ros_msg.data_query) - ros_msg.data_query_is_set = proto.HasField("data_query") - - -def convert_bosdyn_msgs_get_data_index_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataIndexRequest", proto: "bosdyn.api.data_index_pb2.GetDataIndexRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.data_query_is_set: - convert_bosdyn_msgs_data_query_to_proto(ros_msg.data_query, proto.data_query) - - -def convert_proto_to_bosdyn_msgs_get_events_comments_request(proto: "bosdyn.api.data_index_pb2.GetEventsCommentsRequest", ros_msg: "bosdyn_msgs.msgs.GetEventsCommentsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_events_comments_spec(proto.event_comment_request, ros_msg.event_comment_request) - ros_msg.event_comment_request_is_set = proto.HasField("event_comment_request") - - -def convert_bosdyn_msgs_get_events_comments_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEventsCommentsRequest", proto: "bosdyn.api.data_index_pb2.GetEventsCommentsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.event_comment_request_is_set: - convert_bosdyn_msgs_events_comments_spec_to_proto(ros_msg.event_comment_request, proto.event_comment_request) - - -def convert_proto_to_bosdyn_msgs_get_events_comments_response(proto: "bosdyn.api.data_index_pb2.GetEventsCommentsResponse", ros_msg: "bosdyn_msgs.msgs.GetEventsCommentsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_events_comments(proto.events_comments, ros_msg.events_comments) - ros_msg.events_comments_is_set = proto.HasField("events_comments") - - -def convert_bosdyn_msgs_get_events_comments_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEventsCommentsResponse", proto: "bosdyn.api.data_index_pb2.GetEventsCommentsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.events_comments_is_set: - convert_bosdyn_msgs_events_comments_to_proto(ros_msg.events_comments, proto.events_comments) - - -def convert_proto_to_bosdyn_msgs_get_data_buffer_status_request(proto: "bosdyn.api.data_index_pb2.GetDataBufferStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetDataBufferStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.get_blob_specs = proto.get_blob_specs - - -def convert_bosdyn_msgs_get_data_buffer_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataBufferStatusRequest", proto: "bosdyn.api.data_index_pb2.GetDataBufferStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.get_blob_specs = ros_msg.get_blob_specs - - -def convert_proto_to_bosdyn_msgs_get_data_buffer_status_response(proto: "bosdyn.api.data_index_pb2.GetDataBufferStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetDataBufferStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_buffer_status(proto.data_buffer_status, ros_msg.data_buffer_status) - ros_msg.data_buffer_status_is_set = proto.HasField("data_buffer_status") - - -def convert_bosdyn_msgs_get_data_buffer_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataBufferStatusResponse", proto: "bosdyn.api.data_index_pb2.GetDataBufferStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.data_buffer_status_is_set: - convert_bosdyn_msgs_data_buffer_status_to_proto(ros_msg.data_buffer_status, proto.data_buffer_status) - - -def convert_proto_to_bosdyn_msgs_get_data_pages_request(proto: "bosdyn.api.data_index_pb2.GetDataPagesRequest", ros_msg: "bosdyn_msgs.msgs.GetDataPagesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - - -def convert_bosdyn_msgs_get_data_pages_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataPagesRequest", proto: "bosdyn.api.data_index_pb2.GetDataPagesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - - -def convert_proto_to_bosdyn_msgs_get_data_pages_response(proto: "bosdyn.api.data_index_pb2.GetDataPagesResponse", ros_msg: "bosdyn_msgs.msgs.GetDataPagesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import PageInfo - ros_msg.pages = [] - for _item in proto.pages: - ros_msg.pages.append(PageInfo()) - convert_proto_to_bosdyn_msgs_page_info(_item, ros_msg.pages[-1]) - - -def convert_bosdyn_msgs_get_data_pages_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDataPagesResponse", proto: "bosdyn.api.data_index_pb2.GetDataPagesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.pages[:] - for _item in ros_msg.pages: - convert_bosdyn_msgs_page_info_to_proto(_item, proto.pages.add()) - - -def convert_proto_to_bosdyn_msgs_delete_data_pages_request(proto: "bosdyn.api.data_index_pb2.DeleteDataPagesRequest", ros_msg: "bosdyn_msgs.msgs.DeleteDataPagesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_time_range(proto.time_range, ros_msg.time_range) - ros_msg.time_range_is_set = proto.HasField("time_range") - ros_msg.page_ids = [] - for _item in proto.page_ids: - ros_msg.page_ids.append(_item) - - -def convert_bosdyn_msgs_delete_data_pages_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteDataPagesRequest", proto: "bosdyn.api.data_index_pb2.DeleteDataPagesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.time_range_is_set: - convert_bosdyn_msgs_time_range_to_proto(ros_msg.time_range, proto.time_range) - del proto.page_ids[:] - for _item in ros_msg.page_ids: - proto.page_ids.append(_item) - - -def convert_proto_to_bosdyn_msgs_delete_page_status_status(proto: "bosdyn.api.data_index_pb2.DeletePageStatus.Status", ros_msg: "bosdyn_msgs.msgs.DeletePageStatusStatus") -> None: - pass - - -def convert_bosdyn_msgs_delete_page_status_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DeletePageStatusStatus", proto: "bosdyn.api.data_index_pb2.DeletePageStatus.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_delete_page_status(proto: "bosdyn.api.data_index_pb2.DeletePageStatus", ros_msg: "bosdyn_msgs.msgs.DeletePageStatus") -> None: - ros_msg.page_id = proto.page_id - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_delete_page_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DeletePageStatus", proto: "bosdyn.api.data_index_pb2.DeletePageStatus") -> None: - proto.Clear() - proto.page_id = ros_msg.page_id - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_delete_data_pages_response(proto: "bosdyn.api.data_index_pb2.DeleteDataPagesResponse", ros_msg: "bosdyn_msgs.msgs.DeleteDataPagesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.bytes_deleted = proto.bytes_deleted - from bosdyn_msgs.msg import DeletePageStatus - ros_msg.status = [] - for _item in proto.status: - ros_msg.status.append(DeletePageStatus()) - convert_proto_to_bosdyn_msgs_delete_page_status(_item, ros_msg.status[-1]) - - -def convert_bosdyn_msgs_delete_data_pages_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteDataPagesResponse", proto: "bosdyn.api.data_index_pb2.DeleteDataPagesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.bytes_deleted = ros_msg.bytes_deleted - del proto.status[:] - for _item in ros_msg.status: - convert_bosdyn_msgs_delete_page_status_to_proto(_item, proto.status.add()) - - -def convert_proto_to_bosdyn_msgs_service_entry_one_of_service_type(proto: "bosdyn.api.directory_pb2.ServiceEntry", ros_msg: "bosdyn_msgs.msgs.ServiceEntryOneOfServiceType") -> None: - if proto.HasField("type"): - ros_msg.service_type_choice = ros_msg.SERVICE_TYPE_TYPE_SET - ros_msg.type = proto.type - - -def convert_bosdyn_msgs_service_entry_one_of_service_type_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceEntryOneOfServiceType", proto: "bosdyn.api.directory_pb2.ServiceEntry") -> None: - proto.ClearField("service_type") - if ros_msg.service_type_choice == ros_msg.SERVICE_TYPE_TYPE_SET: - proto.type = ros_msg.type - - -def convert_proto_to_bosdyn_msgs_service_entry(proto: "bosdyn.api.directory_pb2.ServiceEntry", ros_msg: "bosdyn_msgs.msgs.ServiceEntry") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_service_entry_one_of_service_type(proto, ros_msg.service_type) - ros_msg.authority = proto.authority - convert_proto_to_builtin_interfaces_time(proto.last_update, ros_msg.last_update) - ros_msg.last_update_is_set = proto.HasField("last_update") - ros_msg.user_token_required = proto.user_token_required - ros_msg.permission_required = proto.permission_required - ros_msg.liveness_timeout_secs = proto.liveness_timeout_secs - ros_msg.host_payload_guid = proto.host_payload_guid - - -def convert_bosdyn_msgs_service_entry_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceEntry", proto: "bosdyn.api.directory_pb2.ServiceEntry") -> None: - proto.Clear() - proto.name = ros_msg.name - convert_bosdyn_msgs_service_entry_one_of_service_type_to_proto(ros_msg.service_type, proto) - proto.authority = ros_msg.authority - if ros_msg.last_update_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.last_update, proto.last_update) - proto.user_token_required = ros_msg.user_token_required - proto.permission_required = ros_msg.permission_required - proto.liveness_timeout_secs = ros_msg.liveness_timeout_secs - proto.host_payload_guid = ros_msg.host_payload_guid - - -def convert_proto_to_bosdyn_msgs_endpoint(proto: "bosdyn.api.directory_pb2.Endpoint", ros_msg: "bosdyn_msgs.msgs.Endpoint") -> None: - ros_msg.host_ip = proto.host_ip - ros_msg.port = proto.port - - -def convert_bosdyn_msgs_endpoint_to_proto(ros_msg: "bosdyn_msgs.msgs.Endpoint", proto: "bosdyn.api.directory_pb2.Endpoint") -> None: - proto.Clear() - proto.host_ip = ros_msg.host_ip - proto.port = ros_msg.port - - -def convert_proto_to_bosdyn_msgs_get_service_entry_request(proto: "bosdyn.api.directory_pb2.GetServiceEntryRequest", ros_msg: "bosdyn_msgs.msgs.GetServiceEntryRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.service_name = proto.service_name - - -def convert_bosdyn_msgs_get_service_entry_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetServiceEntryRequest", proto: "bosdyn.api.directory_pb2.GetServiceEntryRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.service_name = ros_msg.service_name - - -def convert_proto_to_bosdyn_msgs_get_service_entry_response_status(proto: "bosdyn.api.directory_pb2.GetServiceEntryResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetServiceEntryResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_service_entry_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetServiceEntryResponseStatus", proto: "bosdyn.api.directory_pb2.GetServiceEntryResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_service_entry_response(proto: "bosdyn.api.directory_pb2.GetServiceEntryResponse", ros_msg: "bosdyn_msgs.msgs.GetServiceEntryResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_service_entry(proto.service_entry, ros_msg.service_entry) - ros_msg.service_entry_is_set = proto.HasField("service_entry") - - -def convert_bosdyn_msgs_get_service_entry_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetServiceEntryResponse", proto: "bosdyn.api.directory_pb2.GetServiceEntryResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.service_entry_is_set: - convert_bosdyn_msgs_service_entry_to_proto(ros_msg.service_entry, proto.service_entry) - - -def convert_proto_to_bosdyn_msgs_list_service_entries_request(proto: "bosdyn.api.directory_pb2.ListServiceEntriesRequest", ros_msg: "bosdyn_msgs.msgs.ListServiceEntriesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_service_entries_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListServiceEntriesRequest", proto: "bosdyn.api.directory_pb2.ListServiceEntriesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_service_entries_response(proto: "bosdyn.api.directory_pb2.ListServiceEntriesResponse", ros_msg: "bosdyn_msgs.msgs.ListServiceEntriesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ServiceEntry - ros_msg.service_entries = [] - for _item in proto.service_entries: - ros_msg.service_entries.append(ServiceEntry()) - convert_proto_to_bosdyn_msgs_service_entry(_item, ros_msg.service_entries[-1]) - - -def convert_bosdyn_msgs_list_service_entries_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListServiceEntriesResponse", proto: "bosdyn.api.directory_pb2.ListServiceEntriesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.service_entries[:] - for _item in ros_msg.service_entries: - convert_bosdyn_msgs_service_entry_to_proto(_item, proto.service_entries.add()) - - -def convert_proto_to_bosdyn_msgs_register_service_request(proto: "bosdyn.api.directory_registration_pb2.RegisterServiceRequest", ros_msg: "bosdyn_msgs.msgs.RegisterServiceRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_endpoint(proto.endpoint, ros_msg.endpoint) - ros_msg.endpoint_is_set = proto.HasField("endpoint") - convert_proto_to_bosdyn_msgs_service_entry(proto.service_entry, ros_msg.service_entry) - ros_msg.service_entry_is_set = proto.HasField("service_entry") - - -def convert_bosdyn_msgs_register_service_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterServiceRequest", proto: "bosdyn.api.directory_registration_pb2.RegisterServiceRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.endpoint_is_set: - convert_bosdyn_msgs_endpoint_to_proto(ros_msg.endpoint, proto.endpoint) - if ros_msg.service_entry_is_set: - convert_bosdyn_msgs_service_entry_to_proto(ros_msg.service_entry, proto.service_entry) - - -def convert_proto_to_bosdyn_msgs_register_service_response_status(proto: "bosdyn.api.directory_registration_pb2.RegisterServiceResponse.Status", ros_msg: "bosdyn_msgs.msgs.RegisterServiceResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_register_service_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterServiceResponseStatus", proto: "bosdyn.api.directory_registration_pb2.RegisterServiceResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_register_service_response(proto: "bosdyn.api.directory_registration_pb2.RegisterServiceResponse", ros_msg: "bosdyn_msgs.msgs.RegisterServiceResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_register_service_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterServiceResponse", proto: "bosdyn.api.directory_registration_pb2.RegisterServiceResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_unregister_service_request(proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceRequest", ros_msg: "bosdyn_msgs.msgs.UnregisterServiceRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.service_name = proto.service_name - - -def convert_bosdyn_msgs_unregister_service_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UnregisterServiceRequest", proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.service_name = ros_msg.service_name - - -def convert_proto_to_bosdyn_msgs_unregister_service_response_status(proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceResponse.Status", ros_msg: "bosdyn_msgs.msgs.UnregisterServiceResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_unregister_service_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UnregisterServiceResponseStatus", proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_unregister_service_response(proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceResponse", ros_msg: "bosdyn_msgs.msgs.UnregisterServiceResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_unregister_service_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UnregisterServiceResponse", proto: "bosdyn.api.directory_registration_pb2.UnregisterServiceResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_update_service_request(proto: "bosdyn.api.directory_registration_pb2.UpdateServiceRequest", ros_msg: "bosdyn_msgs.msgs.UpdateServiceRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_endpoint(proto.endpoint, ros_msg.endpoint) - ros_msg.endpoint_is_set = proto.HasField("endpoint") - convert_proto_to_bosdyn_msgs_service_entry(proto.service_entry, ros_msg.service_entry) - ros_msg.service_entry_is_set = proto.HasField("service_entry") - - -def convert_bosdyn_msgs_update_service_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateServiceRequest", proto: "bosdyn.api.directory_registration_pb2.UpdateServiceRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.endpoint_is_set: - convert_bosdyn_msgs_endpoint_to_proto(ros_msg.endpoint, proto.endpoint) - if ros_msg.service_entry_is_set: - convert_bosdyn_msgs_service_entry_to_proto(ros_msg.service_entry, proto.service_entry) - - -def convert_proto_to_bosdyn_msgs_update_service_response_status(proto: "bosdyn.api.directory_registration_pb2.UpdateServiceResponse.Status", ros_msg: "bosdyn_msgs.msgs.UpdateServiceResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_update_service_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateServiceResponseStatus", proto: "bosdyn.api.directory_registration_pb2.UpdateServiceResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_service_response(proto: "bosdyn.api.directory_registration_pb2.UpdateServiceResponse", ros_msg: "bosdyn_msgs.msgs.UpdateServiceResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_update_service_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateServiceResponse", proto: "bosdyn.api.directory_registration_pb2.UpdateServiceResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_docking_command_request(proto: "bosdyn.api.docking.docking_pb2.DockingCommandRequest", ros_msg: "bosdyn_msgs.msgs.DockingCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.docking_station_id = proto.docking_station_id - ros_msg.clock_identifier = proto.clock_identifier - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.prep_pose_behavior.value = proto.prep_pose_behavior - ros_msg.require_fiducial = proto.require_fiducial - - -def convert_bosdyn_msgs_docking_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandRequest", proto: "bosdyn.api.docking.docking_pb2.DockingCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.docking_station_id = ros_msg.docking_station_id - proto.clock_identifier = ros_msg.clock_identifier - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.prep_pose_behavior = ros_msg.prep_pose_behavior.value - proto.require_fiducial = ros_msg.require_fiducial - - -def convert_proto_to_bosdyn_msgs_docking_command_response_status(proto: "bosdyn.api.docking.docking_pb2.DockingCommandResponse.Status", ros_msg: "bosdyn_msgs.msgs.DockingCommandResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_docking_command_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandResponseStatus", proto: "bosdyn.api.docking.docking_pb2.DockingCommandResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_docking_command_response(proto: "bosdyn.api.docking.docking_pb2.DockingCommandResponse", ros_msg: "bosdyn_msgs.msgs.DockingCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.docking_command_id = proto.docking_command_id - - -def convert_bosdyn_msgs_docking_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandResponse", proto: "bosdyn.api.docking.docking_pb2.DockingCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.docking_command_id = ros_msg.docking_command_id - - -def convert_proto_to_bosdyn_msgs_update_docking_params(proto: "bosdyn.api.docking.docking_pb2.UpdateDockingParams", ros_msg: "bosdyn_msgs.msgs.UpdateDockingParams") -> None: - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - - -def convert_bosdyn_msgs_update_docking_params_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateDockingParams", proto: "bosdyn.api.docking.docking_pb2.UpdateDockingParams") -> None: - proto.Clear() - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - - -def convert_proto_to_bosdyn_msgs_docking_command_feedback_request(proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.docking_command_id = proto.docking_command_id - convert_proto_to_bosdyn_msgs_update_docking_params(proto.update_docking_params, ros_msg.update_docking_params) - ros_msg.update_docking_params_is_set = proto.HasField("update_docking_params") - - -def convert_bosdyn_msgs_docking_command_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackRequest", proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.docking_command_id = ros_msg.docking_command_id - if ros_msg.update_docking_params_is_set: - convert_bosdyn_msgs_update_docking_params_to_proto(ros_msg.update_docking_params, proto.update_docking_params) - - -def convert_proto_to_bosdyn_msgs_docking_command_feedback_response_status(proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_docking_command_feedback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackResponseStatus", proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_docking_command_feedback_response(proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_docking_command_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DockingCommandFeedbackResponse", proto: "bosdyn.api.docking.docking_pb2.DockingCommandFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_dock_type(proto: "bosdyn.api.docking.docking_pb2.DockType", ros_msg: "bosdyn_msgs.msgs.DockType") -> None: - pass - - -def convert_bosdyn_msgs_dock_type_to_proto(ros_msg: "bosdyn_msgs.msgs.DockType", proto: "bosdyn.api.docking.docking_pb2.DockType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_config_range(proto: "bosdyn.api.docking.docking_pb2.ConfigRange", ros_msg: "bosdyn_msgs.msgs.ConfigRange") -> None: - ros_msg.id_start = proto.id_start - ros_msg.id_end = proto.id_end - ros_msg.type.value = proto.type - - -def convert_bosdyn_msgs_config_range_to_proto(ros_msg: "bosdyn_msgs.msgs.ConfigRange", proto: "bosdyn.api.docking.docking_pb2.ConfigRange") -> None: - proto.Clear() - proto.id_start = ros_msg.id_start - proto.id_end = ros_msg.id_end - proto.type = ros_msg.type.value - - -def convert_proto_to_bosdyn_msgs_get_docking_config_request(proto: "bosdyn.api.docking.docking_pb2.GetDockingConfigRequest", ros_msg: "bosdyn_msgs.msgs.GetDockingConfigRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_docking_config_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDockingConfigRequest", proto: "bosdyn.api.docking.docking_pb2.GetDockingConfigRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_docking_config_response(proto: "bosdyn.api.docking.docking_pb2.GetDockingConfigResponse", ros_msg: "bosdyn_msgs.msgs.GetDockingConfigResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ConfigRange - ros_msg.dock_configs = [] - for _item in proto.dock_configs: - ros_msg.dock_configs.append(ConfigRange()) - convert_proto_to_bosdyn_msgs_config_range(_item, ros_msg.dock_configs[-1]) - - -def convert_bosdyn_msgs_get_docking_config_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDockingConfigResponse", proto: "bosdyn.api.docking.docking_pb2.GetDockingConfigResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.dock_configs[:] - for _item in ros_msg.dock_configs: - convert_bosdyn_msgs_config_range_to_proto(_item, proto.dock_configs.add()) - - -def convert_proto_to_bosdyn_msgs_prep_pose_behavior(proto: "bosdyn.api.docking.docking_pb2.PrepPoseBehavior", ros_msg: "bosdyn_msgs.msgs.PrepPoseBehavior") -> None: - pass - - -def convert_bosdyn_msgs_prep_pose_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.PrepPoseBehavior", proto: "bosdyn.api.docking.docking_pb2.PrepPoseBehavior") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_dock_state_docked_status(proto: "bosdyn.api.docking.docking_pb2.DockState.DockedStatus", ros_msg: "bosdyn_msgs.msgs.DockStateDockedStatus") -> None: - pass - - -def convert_bosdyn_msgs_dock_state_docked_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DockStateDockedStatus", proto: "bosdyn.api.docking.docking_pb2.DockState.DockedStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_dock_state_link_status(proto: "bosdyn.api.docking.docking_pb2.DockState.LinkStatus", ros_msg: "bosdyn_msgs.msgs.DockStateLinkStatus") -> None: - pass - - -def convert_bosdyn_msgs_dock_state_link_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DockStateLinkStatus", proto: "bosdyn.api.docking.docking_pb2.DockState.LinkStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_dock_state(proto: "bosdyn.api.docking.docking_pb2.DockState", ros_msg: "bosdyn_msgs.msgs.DockState") -> None: - ros_msg.status.value = proto.status - ros_msg.dock_type.value = proto.dock_type - ros_msg.dock_id = proto.dock_id - ros_msg.power_status.value = proto.power_status - - -def convert_bosdyn_msgs_dock_state_to_proto(ros_msg: "bosdyn_msgs.msgs.DockState", proto: "bosdyn.api.docking.docking_pb2.DockState") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.dock_type = ros_msg.dock_type.value - proto.dock_id = ros_msg.dock_id - proto.power_status = ros_msg.power_status.value - - -def convert_proto_to_bosdyn_msgs_get_docking_state_request(proto: "bosdyn.api.docking.docking_pb2.GetDockingStateRequest", ros_msg: "bosdyn_msgs.msgs.GetDockingStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_docking_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDockingStateRequest", proto: "bosdyn.api.docking.docking_pb2.GetDockingStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_docking_state_response(proto: "bosdyn.api.docking.docking_pb2.GetDockingStateResponse", ros_msg: "bosdyn_msgs.msgs.GetDockingStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_dock_state(proto.dock_state, ros_msg.dock_state) - ros_msg.dock_state_is_set = proto.HasField("dock_state") - - -def convert_bosdyn_msgs_get_docking_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetDockingStateResponse", proto: "bosdyn.api.docking.docking_pb2.GetDockingStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.dock_state_is_set: - convert_bosdyn_msgs_dock_state_to_proto(ros_msg.dock_state, proto.dock_state) - - -def convert_proto_to_bosdyn_msgs_estop_endpoint(proto: "bosdyn.api.estop_pb2.EstopEndpoint", ros_msg: "bosdyn_msgs.msgs.EstopEndpoint") -> None: - ros_msg.role = proto.role - ros_msg.name = proto.name - ros_msg.unique_id = proto.unique_id - convert_proto_to_builtin_interfaces_duration(proto.timeout, ros_msg.timeout) - ros_msg.timeout_is_set = proto.HasField("timeout") - convert_proto_to_builtin_interfaces_duration(proto.cut_power_timeout, ros_msg.cut_power_timeout) - ros_msg.cut_power_timeout_is_set = proto.HasField("cut_power_timeout") - - -def convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopEndpoint", proto: "bosdyn.api.estop_pb2.EstopEndpoint") -> None: - proto.Clear() - proto.role = ros_msg.role - proto.name = ros_msg.name - proto.unique_id = ros_msg.unique_id - if ros_msg.timeout_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.timeout, proto.timeout) - if ros_msg.cut_power_timeout_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.cut_power_timeout, proto.cut_power_timeout) - - -def convert_proto_to_bosdyn_msgs_estop_stop_level(proto: "bosdyn.api.estop_pb2.EstopStopLevel", ros_msg: "bosdyn_msgs.msgs.EstopStopLevel") -> None: - pass - - -def convert_bosdyn_msgs_estop_stop_level_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopStopLevel", proto: "bosdyn.api.estop_pb2.EstopStopLevel") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_estop_config(proto: "bosdyn.api.estop_pb2.EstopConfig", ros_msg: "bosdyn_msgs.msgs.EstopConfig") -> None: - from bosdyn_msgs.msg import EstopEndpoint - ros_msg.endpoints = [] - for _item in proto.endpoints: - ros_msg.endpoints.append(EstopEndpoint()) - convert_proto_to_bosdyn_msgs_estop_endpoint(_item, ros_msg.endpoints[-1]) - ros_msg.unique_id = proto.unique_id - - -def convert_bosdyn_msgs_estop_config_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopConfig", proto: "bosdyn.api.estop_pb2.EstopConfig") -> None: - proto.Clear() - del proto.endpoints[:] - for _item in ros_msg.endpoints: - convert_bosdyn_msgs_estop_endpoint_to_proto(_item, proto.endpoints.add()) - proto.unique_id = ros_msg.unique_id - - -def convert_proto_to_bosdyn_msgs_estop_endpoint_with_status(proto: "bosdyn.api.estop_pb2.EstopEndpointWithStatus", ros_msg: "bosdyn_msgs.msgs.EstopEndpointWithStatus") -> None: - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.endpoint, ros_msg.endpoint) - ros_msg.endpoint_is_set = proto.HasField("endpoint") - ros_msg.stop_level.value = proto.stop_level - convert_proto_to_builtin_interfaces_duration(proto.time_since_valid_response, ros_msg.time_since_valid_response) - ros_msg.time_since_valid_response_is_set = proto.HasField("time_since_valid_response") - - -def convert_bosdyn_msgs_estop_endpoint_with_status_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopEndpointWithStatus", proto: "bosdyn.api.estop_pb2.EstopEndpointWithStatus") -> None: - proto.Clear() - if ros_msg.endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.endpoint, proto.endpoint) - proto.stop_level = ros_msg.stop_level.value - if ros_msg.time_since_valid_response_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_valid_response, proto.time_since_valid_response) - - -def convert_proto_to_bosdyn_msgs_estop_system_status(proto: "bosdyn.api.estop_pb2.EstopSystemStatus", ros_msg: "bosdyn_msgs.msgs.EstopSystemStatus") -> None: - from bosdyn_msgs.msg import EstopEndpointWithStatus - ros_msg.endpoints = [] - for _item in proto.endpoints: - ros_msg.endpoints.append(EstopEndpointWithStatus()) - convert_proto_to_bosdyn_msgs_estop_endpoint_with_status(_item, ros_msg.endpoints[-1]) - ros_msg.stop_level.value = proto.stop_level - ros_msg.stop_level_details = proto.stop_level_details - - -def convert_bosdyn_msgs_estop_system_status_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopSystemStatus", proto: "bosdyn.api.estop_pb2.EstopSystemStatus") -> None: - proto.Clear() - del proto.endpoints[:] - for _item in ros_msg.endpoints: - convert_bosdyn_msgs_estop_endpoint_with_status_to_proto(_item, proto.endpoints.add()) - proto.stop_level = ros_msg.stop_level.value - proto.stop_level_details = ros_msg.stop_level_details - - -def convert_proto_to_bosdyn_msgs_estop_check_in_request(proto: "bosdyn.api.estop_pb2.EstopCheckInRequest", ros_msg: "bosdyn_msgs.msgs.EstopCheckInRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.endpoint, ros_msg.endpoint) - ros_msg.endpoint_is_set = proto.HasField("endpoint") - ros_msg.challenge = proto.challenge - ros_msg.response = proto.response - ros_msg.stop_level.value = proto.stop_level - - -def convert_bosdyn_msgs_estop_check_in_request_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopCheckInRequest", proto: "bosdyn.api.estop_pb2.EstopCheckInRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.endpoint, proto.endpoint) - proto.challenge = ros_msg.challenge - proto.response = ros_msg.response - proto.stop_level = ros_msg.stop_level.value - - -def convert_proto_to_bosdyn_msgs_estop_check_in_response_status(proto: "bosdyn.api.estop_pb2.EstopCheckInResponse.Status", ros_msg: "bosdyn_msgs.msgs.EstopCheckInResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_estop_check_in_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopCheckInResponseStatus", proto: "bosdyn.api.estop_pb2.EstopCheckInResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_estop_check_in_response(proto: "bosdyn.api.estop_pb2.EstopCheckInResponse", ros_msg: "bosdyn_msgs.msgs.EstopCheckInResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_check_in_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - ros_msg.challenge = proto.challenge - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_estop_check_in_response_to_proto(ros_msg: "bosdyn_msgs.msgs.EstopCheckInResponse", proto: "bosdyn.api.estop_pb2.EstopCheckInResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.request_is_set: - convert_bosdyn_msgs_estop_check_in_request_to_proto(ros_msg.request, proto.request) - proto.challenge = ros_msg.challenge - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_register_estop_endpoint_request(proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointRequest", ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.target_endpoint, ros_msg.target_endpoint) - ros_msg.target_endpoint_is_set = proto.HasField("target_endpoint") - ros_msg.target_config_id = proto.target_config_id - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.new_endpoint, ros_msg.new_endpoint) - ros_msg.new_endpoint_is_set = proto.HasField("new_endpoint") - - -def convert_bosdyn_msgs_register_estop_endpoint_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointRequest", proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.target_endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.target_endpoint, proto.target_endpoint) - proto.target_config_id = ros_msg.target_config_id - if ros_msg.new_endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.new_endpoint, proto.new_endpoint) - - -def convert_proto_to_bosdyn_msgs_register_estop_endpoint_response_status(proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointResponse.Status", ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_register_estop_endpoint_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointResponseStatus", proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_register_estop_endpoint_response(proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointResponse", ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_register_estop_endpoint_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.new_endpoint, ros_msg.new_endpoint) - ros_msg.new_endpoint_is_set = proto.HasField("new_endpoint") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_register_estop_endpoint_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterEstopEndpointResponse", proto: "bosdyn.api.estop_pb2.RegisterEstopEndpointResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.request_is_set: - convert_bosdyn_msgs_register_estop_endpoint_request_to_proto(ros_msg.request, proto.request) - if ros_msg.new_endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.new_endpoint, proto.new_endpoint) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_deregister_estop_endpoint_request(proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointRequest", ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_endpoint(proto.target_endpoint, ros_msg.target_endpoint) - ros_msg.target_endpoint_is_set = proto.HasField("target_endpoint") - ros_msg.target_config_id = proto.target_config_id - - -def convert_bosdyn_msgs_deregister_estop_endpoint_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointRequest", proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.target_endpoint_is_set: - convert_bosdyn_msgs_estop_endpoint_to_proto(ros_msg.target_endpoint, proto.target_endpoint) - proto.target_config_id = ros_msg.target_config_id - - -def convert_proto_to_bosdyn_msgs_deregister_estop_endpoint_response_status(proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointResponse.Status", ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_deregister_estop_endpoint_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointResponseStatus", proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_deregister_estop_endpoint_response(proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointResponse", ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_deregister_estop_endpoint_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_deregister_estop_endpoint_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DeregisterEstopEndpointResponse", proto: "bosdyn.api.estop_pb2.DeregisterEstopEndpointResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.request_is_set: - convert_bosdyn_msgs_deregister_estop_endpoint_request_to_proto(ros_msg.request, proto.request) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_get_estop_config_request(proto: "bosdyn.api.estop_pb2.GetEstopConfigRequest", ros_msg: "bosdyn_msgs.msgs.GetEstopConfigRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.target_config_id = proto.target_config_id - - -def convert_bosdyn_msgs_get_estop_config_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEstopConfigRequest", proto: "bosdyn.api.estop_pb2.GetEstopConfigRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.target_config_id = ros_msg.target_config_id - - -def convert_proto_to_bosdyn_msgs_get_estop_config_response(proto: "bosdyn.api.estop_pb2.GetEstopConfigResponse", ros_msg: "bosdyn_msgs.msgs.GetEstopConfigResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_get_estop_config_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - convert_proto_to_bosdyn_msgs_estop_config(proto.active_config, ros_msg.active_config) - ros_msg.active_config_is_set = proto.HasField("active_config") - - -def convert_bosdyn_msgs_get_estop_config_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEstopConfigResponse", proto: "bosdyn.api.estop_pb2.GetEstopConfigResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.request_is_set: - convert_bosdyn_msgs_get_estop_config_request_to_proto(ros_msg.request, proto.request) - if ros_msg.active_config_is_set: - convert_bosdyn_msgs_estop_config_to_proto(ros_msg.active_config, proto.active_config) - - -def convert_proto_to_bosdyn_msgs_set_estop_config_request(proto: "bosdyn.api.estop_pb2.SetEstopConfigRequest", ros_msg: "bosdyn_msgs.msgs.SetEstopConfigRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_config(proto.config, ros_msg.config) - ros_msg.config_is_set = proto.HasField("config") - ros_msg.target_config_id = proto.target_config_id - - -def convert_bosdyn_msgs_set_estop_config_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetEstopConfigRequest", proto: "bosdyn.api.estop_pb2.SetEstopConfigRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.config_is_set: - convert_bosdyn_msgs_estop_config_to_proto(ros_msg.config, proto.config) - proto.target_config_id = ros_msg.target_config_id - - -def convert_proto_to_bosdyn_msgs_set_estop_config_response_status(proto: "bosdyn.api.estop_pb2.SetEstopConfigResponse.Status", ros_msg: "bosdyn_msgs.msgs.SetEstopConfigResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_set_estop_config_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SetEstopConfigResponseStatus", proto: "bosdyn.api.estop_pb2.SetEstopConfigResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_set_estop_config_response(proto: "bosdyn.api.estop_pb2.SetEstopConfigResponse", ros_msg: "bosdyn_msgs.msgs.SetEstopConfigResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_set_estop_config_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - convert_proto_to_bosdyn_msgs_estop_config(proto.active_config, ros_msg.active_config) - ros_msg.active_config_is_set = proto.HasField("active_config") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_set_estop_config_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetEstopConfigResponse", proto: "bosdyn.api.estop_pb2.SetEstopConfigResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.request_is_set: - convert_bosdyn_msgs_set_estop_config_request_to_proto(ros_msg.request, proto.request) - if ros_msg.active_config_is_set: - convert_bosdyn_msgs_estop_config_to_proto(ros_msg.active_config, proto.active_config) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_get_estop_system_status_request(proto: "bosdyn.api.estop_pb2.GetEstopSystemStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetEstopSystemStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_estop_system_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEstopSystemStatusRequest", proto: "bosdyn.api.estop_pb2.GetEstopSystemStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_estop_system_status_response(proto: "bosdyn.api.estop_pb2.GetEstopSystemStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetEstopSystemStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_estop_system_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_get_estop_system_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetEstopSystemStatusResponse", proto: "bosdyn.api.estop_pb2.GetEstopSystemStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_estop_system_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_full_body_command_request_one_of_command(proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Request", ros_msg: "bosdyn_msgs.msgs.FullBodyCommandRequestOneOfCommand") -> None: - if proto.HasField("stop_request"): - ros_msg.command_choice = ros_msg.COMMAND_STOP_REQUEST_SET - convert_proto_to_bosdyn_msgs_stop_command_request(proto.stop_request, ros_msg.stop_request) - if proto.HasField("freeze_request"): - ros_msg.command_choice = ros_msg.COMMAND_FREEZE_REQUEST_SET - convert_proto_to_bosdyn_msgs_freeze_command_request(proto.freeze_request, ros_msg.freeze_request) - if proto.HasField("selfright_request"): - ros_msg.command_choice = ros_msg.COMMAND_SELFRIGHT_REQUEST_SET - convert_proto_to_bosdyn_msgs_self_right_command_request(proto.selfright_request, ros_msg.selfright_request) - if proto.HasField("safe_power_off_request"): - ros_msg.command_choice = ros_msg.COMMAND_SAFE_POWER_OFF_REQUEST_SET - convert_proto_to_bosdyn_msgs_safe_power_off_command_request(proto.safe_power_off_request, ros_msg.safe_power_off_request) - if proto.HasField("battery_change_pose_request"): - ros_msg.command_choice = ros_msg.COMMAND_BATTERY_CHANGE_POSE_REQUEST_SET - convert_proto_to_bosdyn_msgs_battery_change_pose_command_request(proto.battery_change_pose_request, ros_msg.battery_change_pose_request) - if proto.HasField("payload_estimation_request"): - ros_msg.command_choice = ros_msg.COMMAND_PAYLOAD_ESTIMATION_REQUEST_SET - convert_proto_to_bosdyn_msgs_payload_estimation_command_request(proto.payload_estimation_request, ros_msg.payload_estimation_request) - if proto.HasField("constrained_manipulation_request"): - ros_msg.command_choice = ros_msg.COMMAND_CONSTRAINED_MANIPULATION_REQUEST_SET - convert_proto_to_bosdyn_msgs_constrained_manipulation_command_request(proto.constrained_manipulation_request, ros_msg.constrained_manipulation_request) - - -def convert_bosdyn_msgs_full_body_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.FullBodyCommandRequestOneOfCommand", proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_STOP_REQUEST_SET: - convert_bosdyn_msgs_stop_command_request_to_proto(ros_msg.stop_request, proto.stop_request) - if ros_msg.command_choice == ros_msg.COMMAND_FREEZE_REQUEST_SET: - convert_bosdyn_msgs_freeze_command_request_to_proto(ros_msg.freeze_request, proto.freeze_request) - if ros_msg.command_choice == ros_msg.COMMAND_SELFRIGHT_REQUEST_SET: - convert_bosdyn_msgs_self_right_command_request_to_proto(ros_msg.selfright_request, proto.selfright_request) - if ros_msg.command_choice == ros_msg.COMMAND_SAFE_POWER_OFF_REQUEST_SET: - convert_bosdyn_msgs_safe_power_off_command_request_to_proto(ros_msg.safe_power_off_request, proto.safe_power_off_request) - if ros_msg.command_choice == ros_msg.COMMAND_BATTERY_CHANGE_POSE_REQUEST_SET: - convert_bosdyn_msgs_battery_change_pose_command_request_to_proto(ros_msg.battery_change_pose_request, proto.battery_change_pose_request) - if ros_msg.command_choice == ros_msg.COMMAND_PAYLOAD_ESTIMATION_REQUEST_SET: - convert_bosdyn_msgs_payload_estimation_command_request_to_proto(ros_msg.payload_estimation_request, proto.payload_estimation_request) - if ros_msg.command_choice == ros_msg.COMMAND_CONSTRAINED_MANIPULATION_REQUEST_SET: - convert_bosdyn_msgs_constrained_manipulation_command_request_to_proto(ros_msg.constrained_manipulation_request, proto.constrained_manipulation_request) - - -def convert_proto_to_bosdyn_msgs_full_body_command_request(proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Request", ros_msg: "bosdyn_msgs.msgs.FullBodyCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_full_body_command_request_one_of_command(proto, ros_msg.command) - - -def convert_bosdyn_msgs_full_body_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.FullBodyCommandRequest", proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_full_body_command_request_one_of_command_to_proto(ros_msg.command, proto) - - -def convert_proto_to_bosdyn_msgs_full_body_command_feedback_one_of_feedback(proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.FullBodyCommandFeedbackOneOfFeedback") -> None: - if proto.HasField("stop_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_STOP_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_stop_command_feedback(proto.stop_feedback, ros_msg.stop_feedback) - if proto.HasField("freeze_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_FREEZE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_freeze_command_feedback(proto.freeze_feedback, ros_msg.freeze_feedback) - if proto.HasField("selfright_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_SELFRIGHT_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_self_right_command_feedback(proto.selfright_feedback, ros_msg.selfright_feedback) - if proto.HasField("safe_power_off_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_SAFE_POWER_OFF_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_safe_power_off_command_feedback(proto.safe_power_off_feedback, ros_msg.safe_power_off_feedback) - if proto.HasField("battery_change_pose_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_BATTERY_CHANGE_POSE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_battery_change_pose_command_feedback(proto.battery_change_pose_feedback, ros_msg.battery_change_pose_feedback) - if proto.HasField("payload_estimation_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_PAYLOAD_ESTIMATION_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_payload_estimation_command_feedback(proto.payload_estimation_feedback, ros_msg.payload_estimation_feedback) - if proto.HasField("constrained_manipulation_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_CONSTRAINED_MANIPULATION_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_constrained_manipulation_command_feedback(proto.constrained_manipulation_feedback, ros_msg.constrained_manipulation_feedback) - - -def convert_bosdyn_msgs_full_body_command_feedback_one_of_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.FullBodyCommandFeedbackOneOfFeedback", proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Feedback") -> None: - proto.ClearField("feedback") - if ros_msg.feedback_choice == ros_msg.FEEDBACK_STOP_FEEDBACK_SET: - convert_bosdyn_msgs_stop_command_feedback_to_proto(ros_msg.stop_feedback, proto.stop_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_FREEZE_FEEDBACK_SET: - convert_bosdyn_msgs_freeze_command_feedback_to_proto(ros_msg.freeze_feedback, proto.freeze_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_SELFRIGHT_FEEDBACK_SET: - convert_bosdyn_msgs_self_right_command_feedback_to_proto(ros_msg.selfright_feedback, proto.selfright_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_SAFE_POWER_OFF_FEEDBACK_SET: - convert_bosdyn_msgs_safe_power_off_command_feedback_to_proto(ros_msg.safe_power_off_feedback, proto.safe_power_off_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_BATTERY_CHANGE_POSE_FEEDBACK_SET: - convert_bosdyn_msgs_battery_change_pose_command_feedback_to_proto(ros_msg.battery_change_pose_feedback, proto.battery_change_pose_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_PAYLOAD_ESTIMATION_FEEDBACK_SET: - convert_bosdyn_msgs_payload_estimation_command_feedback_to_proto(ros_msg.payload_estimation_feedback, proto.payload_estimation_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_CONSTRAINED_MANIPULATION_FEEDBACK_SET: - convert_bosdyn_msgs_constrained_manipulation_command_feedback_to_proto(ros_msg.constrained_manipulation_feedback, proto.constrained_manipulation_feedback) - - -def convert_proto_to_bosdyn_msgs_full_body_command_feedback(proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.FullBodyCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_full_body_command_feedback_one_of_feedback(proto, ros_msg.feedback) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_full_body_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.FullBodyCommandFeedback", proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand.Feedback") -> None: - proto.Clear() - convert_bosdyn_msgs_full_body_command_feedback_one_of_feedback_to_proto(ros_msg.feedback, proto) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_full_body_command(proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand", ros_msg: "bosdyn_msgs.msgs.FullBodyCommand") -> None: - pass - - -def convert_bosdyn_msgs_full_body_command_to_proto(ros_msg: "bosdyn_msgs.msgs.FullBodyCommand", proto: "bosdyn.api.full_body_command_pb2.FullBodyCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_vec2(proto: "bosdyn.api.geometry_pb2.Vec2", ros_msg: "bosdyn_msgs.msgs.Vec2") -> None: - ros_msg.x = proto.x - ros_msg.y = proto.y - - -def convert_bosdyn_msgs_vec2_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec2", proto: "bosdyn.api.geometry_pb2.Vec2") -> None: - proto.Clear() - proto.x = ros_msg.x - proto.y = ros_msg.y - - -def convert_proto_to_bosdyn_msgs_vec3(proto: "bosdyn.api.geometry_pb2.Vec3", ros_msg: "bosdyn_msgs.msgs.Vec3") -> None: - ros_msg.x = proto.x - ros_msg.y = proto.y - ros_msg.z = proto.z - - -def convert_bosdyn_msgs_vec3_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec3", proto: "bosdyn.api.geometry_pb2.Vec3") -> None: - proto.Clear() - proto.x = ros_msg.x - proto.y = ros_msg.y - proto.z = ros_msg.z - - -def convert_proto_to_bosdyn_msgs_cylindrical_coordinate(proto: "bosdyn.api.geometry_pb2.CylindricalCoordinate", ros_msg: "bosdyn_msgs.msgs.CylindricalCoordinate") -> None: - ros_msg.r = proto.r - ros_msg.theta = proto.theta - ros_msg.z = proto.z - - -def convert_bosdyn_msgs_cylindrical_coordinate_to_proto(ros_msg: "bosdyn_msgs.msgs.CylindricalCoordinate", proto: "bosdyn.api.geometry_pb2.CylindricalCoordinate") -> None: - proto.Clear() - proto.r = ros_msg.r - proto.theta = ros_msg.theta - proto.z = ros_msg.z - - -def convert_proto_to_bosdyn_msgs_quaternion(proto: "bosdyn.api.geometry_pb2.Quaternion", ros_msg: "bosdyn_msgs.msgs.Quaternion") -> None: - ros_msg.x = proto.x - ros_msg.y = proto.y - ros_msg.z = proto.z - ros_msg.w = proto.w - - -def convert_bosdyn_msgs_quaternion_to_proto(ros_msg: "bosdyn_msgs.msgs.Quaternion", proto: "bosdyn.api.geometry_pb2.Quaternion") -> None: - proto.Clear() - proto.x = ros_msg.x - proto.y = ros_msg.y - proto.z = ros_msg.z - proto.w = ros_msg.w - - -def convert_proto_to_bosdyn_msgs_plane(proto: "bosdyn.api.geometry_pb2.Plane", ros_msg: "bosdyn_msgs.msgs.Plane") -> None: - convert_proto_to_geometry_msgs_vector3(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - convert_proto_to_geometry_msgs_vector3(proto.normal, ros_msg.normal) - ros_msg.normal_is_set = proto.HasField("normal") - - -def convert_bosdyn_msgs_plane_to_proto(ros_msg: "bosdyn_msgs.msgs.Plane", proto: "bosdyn.api.geometry_pb2.Plane") -> None: - proto.Clear() - if ros_msg.point_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.point, proto.point) - if ros_msg.normal_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.normal, proto.normal) - - -def convert_proto_to_bosdyn_msgs_quad(proto: "bosdyn.api.geometry_pb2.Quad", ros_msg: "bosdyn_msgs.msgs.Quad") -> None: - convert_proto_to_geometry_msgs_pose(proto.pose, ros_msg.pose) - ros_msg.pose_is_set = proto.HasField("pose") - ros_msg.size = proto.size - - -def convert_bosdyn_msgs_quad_to_proto(ros_msg: "bosdyn_msgs.msgs.Quad", proto: "bosdyn.api.geometry_pb2.Quad") -> None: - proto.Clear() - if ros_msg.pose_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.pose, proto.pose) - proto.size = ros_msg.size - - -def convert_proto_to_bosdyn_msgs_ray(proto: "bosdyn.api.geometry_pb2.Ray", ros_msg: "bosdyn_msgs.msgs.Ray") -> None: - convert_proto_to_geometry_msgs_vector3(proto.origin, ros_msg.origin) - ros_msg.origin_is_set = proto.HasField("origin") - convert_proto_to_geometry_msgs_vector3(proto.direction, ros_msg.direction) - ros_msg.direction_is_set = proto.HasField("direction") - - -def convert_bosdyn_msgs_ray_to_proto(ros_msg: "bosdyn_msgs.msgs.Ray", proto: "bosdyn.api.geometry_pb2.Ray") -> None: - proto.Clear() - if ros_msg.origin_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.origin, proto.origin) - if ros_msg.direction_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.direction, proto.direction) - - -def convert_proto_to_bosdyn_msgs_se2_pose(proto: "bosdyn.api.geometry_pb2.SE2Pose", ros_msg: "bosdyn_msgs.msgs.SE2Pose") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - ros_msg.angle = proto.angle - - -def convert_bosdyn_msgs_se2_pose_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2Pose", proto: "bosdyn.api.geometry_pb2.SE2Pose") -> None: - proto.Clear() - if ros_msg.position_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.position, proto.position) - proto.angle = ros_msg.angle - - -def convert_proto_to_bosdyn_msgs_se2_velocity(proto: "bosdyn.api.geometry_pb2.SE2Velocity", ros_msg: "bosdyn_msgs.msgs.SE2Velocity") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.linear, ros_msg.linear) - ros_msg.linear_is_set = proto.HasField("linear") - ros_msg.angular = proto.angular - - -def convert_bosdyn_msgs_se2_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2Velocity", proto: "bosdyn.api.geometry_pb2.SE2Velocity") -> None: - proto.Clear() - if ros_msg.linear_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.linear, proto.linear) - proto.angular = ros_msg.angular - - -def convert_proto_to_bosdyn_msgs_se2_velocity_limit(proto: "bosdyn.api.geometry_pb2.SE2VelocityLimit", ros_msg: "bosdyn_msgs.msgs.SE2VelocityLimit") -> None: - convert_proto_to_bosdyn_msgs_se2_velocity(proto.max_vel, ros_msg.max_vel) - ros_msg.max_vel_is_set = proto.HasField("max_vel") - convert_proto_to_bosdyn_msgs_se2_velocity(proto.min_vel, ros_msg.min_vel) - ros_msg.min_vel_is_set = proto.HasField("min_vel") - - -def convert_bosdyn_msgs_se2_velocity_limit_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2VelocityLimit", proto: "bosdyn.api.geometry_pb2.SE2VelocityLimit") -> None: - proto.Clear() - if ros_msg.max_vel_is_set: - convert_bosdyn_msgs_se2_velocity_to_proto(ros_msg.max_vel, proto.max_vel) - if ros_msg.min_vel_is_set: - convert_bosdyn_msgs_se2_velocity_to_proto(ros_msg.min_vel, proto.min_vel) - - -def convert_proto_to_bosdyn_msgs_se3_pose(proto: "bosdyn.api.geometry_pb2.SE3Pose", ros_msg: "bosdyn_msgs.msgs.SE3Pose") -> None: - convert_proto_to_geometry_msgs_vector3(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - convert_proto_to_geometry_msgs_quaternion(proto.rotation, ros_msg.rotation) - ros_msg.rotation_is_set = proto.HasField("rotation") - - -def convert_bosdyn_msgs_se3_pose_to_proto(ros_msg: "bosdyn_msgs.msgs.SE3Pose", proto: "bosdyn.api.geometry_pb2.SE3Pose") -> None: - proto.Clear() - if ros_msg.position_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.position, proto.position) - if ros_msg.rotation_is_set: - convert_geometry_msgs_quaternion_to_proto(ros_msg.rotation, proto.rotation) - - -def convert_proto_to_bosdyn_msgs_se3_velocity(proto: "bosdyn.api.geometry_pb2.SE3Velocity", ros_msg: "bosdyn_msgs.msgs.SE3Velocity") -> None: - convert_proto_to_geometry_msgs_vector3(proto.linear, ros_msg.linear) - ros_msg.linear_is_set = proto.HasField("linear") - convert_proto_to_geometry_msgs_vector3(proto.angular, ros_msg.angular) - ros_msg.angular_is_set = proto.HasField("angular") - - -def convert_bosdyn_msgs_se3_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.SE3Velocity", proto: "bosdyn.api.geometry_pb2.SE3Velocity") -> None: - proto.Clear() - if ros_msg.linear_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.linear, proto.linear) - if ros_msg.angular_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.angular, proto.angular) - - -def convert_proto_to_bosdyn_msgs_wrench(proto: "bosdyn.api.geometry_pb2.Wrench", ros_msg: "bosdyn_msgs.msgs.Wrench") -> None: - convert_proto_to_geometry_msgs_vector3(proto.force, ros_msg.force) - ros_msg.force_is_set = proto.HasField("force") - convert_proto_to_geometry_msgs_vector3(proto.torque, ros_msg.torque) - ros_msg.torque_is_set = proto.HasField("torque") - - -def convert_bosdyn_msgs_wrench_to_proto(ros_msg: "bosdyn_msgs.msgs.Wrench", proto: "bosdyn.api.geometry_pb2.Wrench") -> None: - proto.Clear() - if ros_msg.force_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.force, proto.force) - if ros_msg.torque_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.torque, proto.torque) - - -def convert_proto_to_bosdyn_msgs_frame_tree_snapshot_parent_edge(proto: "bosdyn.api.geometry_pb2.FrameTreeSnapshot.ParentEdge", ros_msg: "bosdyn_msgs.msgs.FrameTreeSnapshotParentEdge") -> None: - ros_msg.parent_frame_name = proto.parent_frame_name - convert_proto_to_geometry_msgs_pose(proto.parent_tform_child, ros_msg.parent_tform_child) - ros_msg.parent_tform_child_is_set = proto.HasField("parent_tform_child") - - -def convert_bosdyn_msgs_frame_tree_snapshot_parent_edge_to_proto(ros_msg: "bosdyn_msgs.msgs.FrameTreeSnapshotParentEdge", proto: "bosdyn.api.geometry_pb2.FrameTreeSnapshot.ParentEdge") -> None: - proto.Clear() - proto.parent_frame_name = ros_msg.parent_frame_name - if ros_msg.parent_tform_child_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.parent_tform_child, proto.parent_tform_child) - - -def convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto: "bosdyn.api.geometry_pb2.FrameTreeSnapshot", ros_msg: "bosdyn_msgs.msgs.FrameTreeSnapshot") -> None: - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsFrameTreeSnapshotParentEdge - ros_msg.child_to_parent_edge_map = [] - for _item in proto.child_to_parent_edge_map: - ros_msg.child_to_parent_edge_map.append(KeyStringValueBosdynMsgsFrameTreeSnapshotParentEdge()) - ros_msg.child_to_parent_edge_map[-1].key = _item - convert_proto_to_bosdyn_msgs_frame_tree_snapshot_parent_edge(proto.child_to_parent_edge_map[_item], ros_msg.child_to_parent_edge_map[-1].value) - - -def convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg: "bosdyn_msgs.msgs.FrameTreeSnapshot", proto: "bosdyn.api.geometry_pb2.FrameTreeSnapshot") -> None: - proto.Clear() - for _item in ros_msg.child_to_parent_edge_map: - convert_bosdyn_msgs_frame_tree_snapshot_parent_edge_to_proto(_item.value, proto.child_to_parent_edge_map[_item.key]) - - -def convert_proto_to_bosdyn_msgs_box2(proto: "bosdyn.api.geometry_pb2.Box2", ros_msg: "bosdyn_msgs.msgs.Box2") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.size, ros_msg.size) - ros_msg.size_is_set = proto.HasField("size") - - -def convert_bosdyn_msgs_box2_to_proto(ros_msg: "bosdyn_msgs.msgs.Box2", proto: "bosdyn.api.geometry_pb2.Box2") -> None: - proto.Clear() - if ros_msg.size_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.size, proto.size) - - -def convert_proto_to_bosdyn_msgs_box2_with_frame(proto: "bosdyn.api.geometry_pb2.Box2WithFrame", ros_msg: "bosdyn_msgs.msgs.Box2WithFrame") -> None: - convert_proto_to_bosdyn_msgs_box2(proto.box, ros_msg.box) - ros_msg.box_is_set = proto.HasField("box") - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_pose(proto.frame_name_tform_box, ros_msg.frame_name_tform_box) - ros_msg.frame_name_tform_box_is_set = proto.HasField("frame_name_tform_box") - - -def convert_bosdyn_msgs_box2_with_frame_to_proto(ros_msg: "bosdyn_msgs.msgs.Box2WithFrame", proto: "bosdyn.api.geometry_pb2.Box2WithFrame") -> None: - proto.Clear() - if ros_msg.box_is_set: - convert_bosdyn_msgs_box2_to_proto(ros_msg.box, proto.box) - proto.frame_name = ros_msg.frame_name - if ros_msg.frame_name_tform_box_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.frame_name_tform_box, proto.frame_name_tform_box) - - -def convert_proto_to_bosdyn_msgs_box3(proto: "bosdyn.api.geometry_pb2.Box3", ros_msg: "bosdyn_msgs.msgs.Box3") -> None: - convert_proto_to_geometry_msgs_vector3(proto.size, ros_msg.size) - ros_msg.size_is_set = proto.HasField("size") - - -def convert_bosdyn_msgs_box3_to_proto(ros_msg: "bosdyn_msgs.msgs.Box3", proto: "bosdyn.api.geometry_pb2.Box3") -> None: - proto.Clear() - if ros_msg.size_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.size, proto.size) - - -def convert_proto_to_bosdyn_msgs_box3_with_frame(proto: "bosdyn.api.geometry_pb2.Box3WithFrame", ros_msg: "bosdyn_msgs.msgs.Box3WithFrame") -> None: - convert_proto_to_bosdyn_msgs_box3(proto.box, ros_msg.box) - ros_msg.box_is_set = proto.HasField("box") - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_pose(proto.frame_name_tform_box, ros_msg.frame_name_tform_box) - ros_msg.frame_name_tform_box_is_set = proto.HasField("frame_name_tform_box") - - -def convert_bosdyn_msgs_box3_with_frame_to_proto(ros_msg: "bosdyn_msgs.msgs.Box3WithFrame", proto: "bosdyn.api.geometry_pb2.Box3WithFrame") -> None: - proto.Clear() - if ros_msg.box_is_set: - convert_bosdyn_msgs_box3_to_proto(ros_msg.box, proto.box) - proto.frame_name = ros_msg.frame_name - if ros_msg.frame_name_tform_box_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.frame_name_tform_box, proto.frame_name_tform_box) - - -def convert_proto_to_bosdyn_msgs_matrix(proto: "bosdyn.api.geometry_pb2.Matrix", ros_msg: "bosdyn_msgs.msgs.Matrix") -> None: - ros_msg.rows = proto.rows - ros_msg.cols = proto.cols - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(_item) - - -def convert_bosdyn_msgs_matrix_to_proto(ros_msg: "bosdyn_msgs.msgs.Matrix", proto: "bosdyn.api.geometry_pb2.Matrix") -> None: - proto.Clear() - proto.rows = ros_msg.rows - proto.cols = ros_msg.cols - del proto.values[:] - for _item in ros_msg.values: - proto.values.append(_item) - - -def convert_proto_to_bosdyn_msgs_matrixf(proto: "bosdyn.api.geometry_pb2.Matrixf", ros_msg: "bosdyn_msgs.msgs.Matrixf") -> None: - ros_msg.rows = proto.rows - ros_msg.cols = proto.cols - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(_item) - - -def convert_bosdyn_msgs_matrixf_to_proto(ros_msg: "bosdyn_msgs.msgs.Matrixf", proto: "bosdyn.api.geometry_pb2.Matrixf") -> None: - proto.Clear() - proto.rows = ros_msg.rows - proto.cols = ros_msg.cols - del proto.values[:] - for _item in ros_msg.values: - proto.values.append(_item) - - -def convert_proto_to_bosdyn_msgs_matrix_int64(proto: "bosdyn.api.geometry_pb2.MatrixInt64", ros_msg: "bosdyn_msgs.msgs.MatrixInt64") -> None: - ros_msg.rows = proto.rows - ros_msg.cols = proto.cols - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(_item) - - -def convert_bosdyn_msgs_matrix_int64_to_proto(ros_msg: "bosdyn_msgs.msgs.MatrixInt64", proto: "bosdyn.api.geometry_pb2.MatrixInt64") -> None: - proto.Clear() - proto.rows = ros_msg.rows - proto.cols = ros_msg.cols - del proto.values[:] - for _item in ros_msg.values: - proto.values.append(_item) - - -def convert_proto_to_bosdyn_msgs_matrix_int32(proto: "bosdyn.api.geometry_pb2.MatrixInt32", ros_msg: "bosdyn_msgs.msgs.MatrixInt32") -> None: - ros_msg.rows = proto.rows - ros_msg.cols = proto.cols - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(_item) - - -def convert_bosdyn_msgs_matrix_int32_to_proto(ros_msg: "bosdyn_msgs.msgs.MatrixInt32", proto: "bosdyn.api.geometry_pb2.MatrixInt32") -> None: - proto.Clear() - proto.rows = ros_msg.rows - proto.cols = ros_msg.cols - del proto.values[:] - for _item in ros_msg.values: - proto.values.append(_item) - - -def convert_proto_to_bosdyn_msgs_vector(proto: "bosdyn.api.geometry_pb2.Vector", ros_msg: "bosdyn_msgs.msgs.Vector") -> None: - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(_item) - - -def convert_bosdyn_msgs_vector_to_proto(ros_msg: "bosdyn_msgs.msgs.Vector", proto: "bosdyn.api.geometry_pb2.Vector") -> None: - proto.Clear() - del proto.values[:] - for _item in ros_msg.values: - proto.values.append(_item) - - -def convert_proto_to_bosdyn_msgs_se3_covariance(proto: "bosdyn.api.geometry_pb2.SE3Covariance", ros_msg: "bosdyn_msgs.msgs.SE3Covariance") -> None: - convert_proto_to_bosdyn_msgs_matrix(proto.matrix, ros_msg.matrix) - ros_msg.matrix_is_set = proto.HasField("matrix") - - -def convert_bosdyn_msgs_se3_covariance_to_proto(ros_msg: "bosdyn_msgs.msgs.SE3Covariance", proto: "bosdyn.api.geometry_pb2.SE3Covariance") -> None: - proto.Clear() - if ros_msg.matrix_is_set: - convert_bosdyn_msgs_matrix_to_proto(ros_msg.matrix, proto.matrix) - - -def convert_proto_to_bosdyn_msgs_poly_line(proto: "bosdyn.api.geometry_pb2.PolyLine", ros_msg: "bosdyn_msgs.msgs.PolyLine") -> None: - from bosdyn_msgs.msg import Vec2 - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(Vec2()) - convert_proto_to_bosdyn_msgs_vec2(_item, ros_msg.points[-1]) - - -def convert_bosdyn_msgs_poly_line_to_proto(ros_msg: "bosdyn_msgs.msgs.PolyLine", proto: "bosdyn.api.geometry_pb2.PolyLine") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_vec2_to_proto(_item, proto.points.add()) - - -def convert_proto_to_bosdyn_msgs_polygon(proto: "bosdyn.api.geometry_pb2.Polygon", ros_msg: "bosdyn_msgs.msgs.Polygon") -> None: - from bosdyn_msgs.msg import Vec2 - ros_msg.vertexes = [] - for _item in proto.vertexes: - ros_msg.vertexes.append(Vec2()) - convert_proto_to_bosdyn_msgs_vec2(_item, ros_msg.vertexes[-1]) - - -def convert_bosdyn_msgs_polygon_to_proto(ros_msg: "bosdyn_msgs.msgs.Polygon", proto: "bosdyn.api.geometry_pb2.Polygon") -> None: - proto.Clear() - del proto.vertexes[:] - for _item in ros_msg.vertexes: - convert_bosdyn_msgs_vec2_to_proto(_item, proto.vertexes.add()) - - -def convert_proto_to_bosdyn_msgs_polygon_with_exclusions(proto: "bosdyn.api.geometry_pb2.PolygonWithExclusions", ros_msg: "bosdyn_msgs.msgs.PolygonWithExclusions") -> None: - convert_proto_to_bosdyn_msgs_polygon(proto.inclusion, ros_msg.inclusion) - ros_msg.inclusion_is_set = proto.HasField("inclusion") - from bosdyn_msgs.msg import Polygon - ros_msg.exclusions = [] - for _item in proto.exclusions: - ros_msg.exclusions.append(Polygon()) - convert_proto_to_bosdyn_msgs_polygon(_item, ros_msg.exclusions[-1]) - - -def convert_bosdyn_msgs_polygon_with_exclusions_to_proto(ros_msg: "bosdyn_msgs.msgs.PolygonWithExclusions", proto: "bosdyn.api.geometry_pb2.PolygonWithExclusions") -> None: - proto.Clear() - if ros_msg.inclusion_is_set: - convert_bosdyn_msgs_polygon_to_proto(ros_msg.inclusion, proto.inclusion) - del proto.exclusions[:] - for _item in ros_msg.exclusions: - convert_bosdyn_msgs_polygon_to_proto(_item, proto.exclusions.add()) - - -def convert_proto_to_bosdyn_msgs_circle(proto: "bosdyn.api.geometry_pb2.Circle", ros_msg: "bosdyn_msgs.msgs.Circle") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.center_pt, ros_msg.center_pt) - ros_msg.center_pt_is_set = proto.HasField("center_pt") - ros_msg.radius = proto.radius - - -def convert_bosdyn_msgs_circle_to_proto(ros_msg: "bosdyn_msgs.msgs.Circle", proto: "bosdyn.api.geometry_pb2.Circle") -> None: - proto.Clear() - if ros_msg.center_pt_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.center_pt, proto.center_pt) - proto.radius = ros_msg.radius - - -def convert_proto_to_bosdyn_msgs_area_one_of_geometry(proto: "bosdyn.api.geometry_pb2.Area", ros_msg: "bosdyn_msgs.msgs.AreaOneOfGeometry") -> None: - if proto.HasField("polygon"): - ros_msg.geometry_choice = ros_msg.GEOMETRY_POLYGON_SET - convert_proto_to_bosdyn_msgs_polygon(proto.polygon, ros_msg.polygon) - if proto.HasField("circle"): - ros_msg.geometry_choice = ros_msg.GEOMETRY_CIRCLE_SET - convert_proto_to_bosdyn_msgs_circle(proto.circle, ros_msg.circle) - - -def convert_bosdyn_msgs_area_one_of_geometry_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaOneOfGeometry", proto: "bosdyn.api.geometry_pb2.Area") -> None: - proto.ClearField("geometry") - if ros_msg.geometry_choice == ros_msg.GEOMETRY_POLYGON_SET: - convert_bosdyn_msgs_polygon_to_proto(ros_msg.polygon, proto.polygon) - if ros_msg.geometry_choice == ros_msg.GEOMETRY_CIRCLE_SET: - convert_bosdyn_msgs_circle_to_proto(ros_msg.circle, proto.circle) - - -def convert_proto_to_bosdyn_msgs_area(proto: "bosdyn.api.geometry_pb2.Area", ros_msg: "bosdyn_msgs.msgs.Area") -> None: - convert_proto_to_bosdyn_msgs_area_one_of_geometry(proto, ros_msg.geometry) - - -def convert_bosdyn_msgs_area_to_proto(ros_msg: "bosdyn_msgs.msgs.Area", proto: "bosdyn.api.geometry_pb2.Area") -> None: - proto.Clear() - convert_bosdyn_msgs_area_one_of_geometry_to_proto(ros_msg.geometry, proto) - - -def convert_proto_to_bosdyn_msgs_volume_one_of_geometry(proto: "bosdyn.api.geometry_pb2.Volume", ros_msg: "bosdyn_msgs.msgs.VolumeOneOfGeometry") -> None: - if proto.HasField("box"): - ros_msg.geometry_choice = ros_msg.GEOMETRY_BOX_SET - convert_proto_to_geometry_msgs_vector3(proto.box, ros_msg.box) - - -def convert_bosdyn_msgs_volume_one_of_geometry_to_proto(ros_msg: "bosdyn_msgs.msgs.VolumeOneOfGeometry", proto: "bosdyn.api.geometry_pb2.Volume") -> None: - proto.ClearField("geometry") - if ros_msg.geometry_choice == ros_msg.GEOMETRY_BOX_SET: - convert_geometry_msgs_vector3_to_proto(ros_msg.box, proto.box) - - -def convert_proto_to_bosdyn_msgs_volume(proto: "bosdyn.api.geometry_pb2.Volume", ros_msg: "bosdyn_msgs.msgs.Volume") -> None: - convert_proto_to_bosdyn_msgs_volume_one_of_geometry(proto, ros_msg.geometry) - - -def convert_bosdyn_msgs_volume_to_proto(ros_msg: "bosdyn_msgs.msgs.Volume", proto: "bosdyn.api.geometry_pb2.Volume") -> None: - proto.Clear() - convert_bosdyn_msgs_volume_one_of_geometry_to_proto(ros_msg.geometry, proto) - - -def convert_proto_to_bosdyn_msgs_bounds(proto: "bosdyn.api.geometry_pb2.Bounds", ros_msg: "bosdyn_msgs.msgs.Bounds") -> None: - ros_msg.lower = proto.lower - ros_msg.upper = proto.upper - - -def convert_bosdyn_msgs_bounds_to_proto(ros_msg: "bosdyn_msgs.msgs.Bounds", proto: "bosdyn.api.geometry_pb2.Bounds") -> None: - proto.Clear() - proto.lower = ros_msg.lower - proto.upper = ros_msg.upper - - -def convert_proto_to_bosdyn_msgs_vec2_value(proto: "bosdyn.api.geometry_pb2.Vec2Value", ros_msg: "bosdyn_msgs.msgs.Vec2Value") -> None: - ros_msg.x = proto.x.value - ros_msg.x_is_set = proto.HasField("x") - ros_msg.y = proto.y.value - ros_msg.y_is_set = proto.HasField("y") - - -def convert_bosdyn_msgs_vec2_value_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec2Value", proto: "bosdyn.api.geometry_pb2.Vec2Value") -> None: - proto.Clear() - if ros_msg.x_is_set: - convert_float64_to_proto(ros_msg.x, proto.x) - if ros_msg.y_is_set: - convert_float64_to_proto(ros_msg.y, proto.y) - - -def convert_proto_to_bosdyn_msgs_vec3_value(proto: "bosdyn.api.geometry_pb2.Vec3Value", ros_msg: "bosdyn_msgs.msgs.Vec3Value") -> None: - ros_msg.x = proto.x.value - ros_msg.x_is_set = proto.HasField("x") - ros_msg.y = proto.y.value - ros_msg.y_is_set = proto.HasField("y") - ros_msg.z = proto.z.value - ros_msg.z_is_set = proto.HasField("z") - - -def convert_bosdyn_msgs_vec3_value_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec3Value", proto: "bosdyn.api.geometry_pb2.Vec3Value") -> None: - proto.Clear() - if ros_msg.x_is_set: - convert_float64_to_proto(ros_msg.x, proto.x) - if ros_msg.y_is_set: - convert_float64_to_proto(ros_msg.y, proto.y) - if ros_msg.z_is_set: - convert_float64_to_proto(ros_msg.z, proto.z) - - -def convert_proto_to_bosdyn_msgs_area_callback_error_call_error(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError.CallError", ros_msg: "bosdyn_msgs.msgs.AreaCallbackErrorCallError") -> None: - pass - - -def convert_bosdyn_msgs_area_callback_error_call_error_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackErrorCallError", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError.CallError") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_area_callback_error_one_of_response_error(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError", ros_msg: "bosdyn_msgs.msgs.AreaCallbackErrorOneOfResponseError") -> None: - if proto.HasField("begin_callback"): - ros_msg.response_error_choice = ros_msg.RESPONSE_ERROR_BEGIN_CALLBACK_SET - convert_proto_to_bosdyn_msgs_begin_callback_response(proto.begin_callback, ros_msg.begin_callback) - if proto.HasField("begin_control"): - ros_msg.response_error_choice = ros_msg.RESPONSE_ERROR_BEGIN_CONTROL_SET - convert_proto_to_bosdyn_msgs_begin_control_response(proto.begin_control, ros_msg.begin_control) - if proto.HasField("update_callback"): - ros_msg.response_error_choice = ros_msg.RESPONSE_ERROR_UPDATE_CALLBACK_SET - convert_proto_to_bosdyn_msgs_update_callback_response(proto.update_callback, ros_msg.update_callback) - if proto.HasField("end_callback"): - ros_msg.response_error_choice = ros_msg.RESPONSE_ERROR_END_CALLBACK_SET - convert_proto_to_bosdyn_msgs_end_callback_response(proto.end_callback, ros_msg.end_callback) - - -def convert_bosdyn_msgs_area_callback_error_one_of_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackErrorOneOfResponseError", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError") -> None: - proto.ClearField("response_error") - if ros_msg.response_error_choice == ros_msg.RESPONSE_ERROR_BEGIN_CALLBACK_SET: - convert_bosdyn_msgs_begin_callback_response_to_proto(ros_msg.begin_callback, proto.begin_callback) - if ros_msg.response_error_choice == ros_msg.RESPONSE_ERROR_BEGIN_CONTROL_SET: - convert_bosdyn_msgs_begin_control_response_to_proto(ros_msg.begin_control, proto.begin_control) - if ros_msg.response_error_choice == ros_msg.RESPONSE_ERROR_UPDATE_CALLBACK_SET: - convert_bosdyn_msgs_update_callback_response_to_proto(ros_msg.update_callback, proto.update_callback) - if ros_msg.response_error_choice == ros_msg.RESPONSE_ERROR_END_CALLBACK_SET: - convert_bosdyn_msgs_end_callback_response_to_proto(ros_msg.end_callback, proto.end_callback) - - -def convert_proto_to_bosdyn_msgs_area_callback_error(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError", ros_msg: "bosdyn_msgs.msgs.AreaCallbackError") -> None: - ros_msg.service_name = proto.service_name - ros_msg.error.value = proto.error - convert_proto_to_bosdyn_msgs_area_callback_error_one_of_response_error(proto, ros_msg.response_error) - - -def convert_bosdyn_msgs_area_callback_error_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackError", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackError") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.error = ros_msg.error.value - convert_bosdyn_msgs_area_callback_error_one_of_response_error_to_proto(ros_msg.response_error, proto) - - -def convert_proto_to_bosdyn_msgs_area_callback_information_request(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformationRequest", ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_area_callback_information_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformationRequest", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_area_callback_information(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformation", ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformation") -> None: - ros_msg.required_lease_resources = [] - for _item in proto.required_lease_resources: - ros_msg.required_lease_resources.append(_item) - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_area_callback_information_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformation", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformation") -> None: - proto.Clear() - del proto.required_lease_resources[:] - for _item in ros_msg.required_lease_resources: - proto.required_lease_resources.append(_item) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_area_callback_information_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformationResponse", ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_area_callback_information(proto.info, ros_msg.info) - ros_msg.info_is_set = proto.HasField("info") - - -def convert_bosdyn_msgs_area_callback_information_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackInformationResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.AreaCallbackInformationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.info_is_set: - convert_bosdyn_msgs_area_callback_information_to_proto(ros_msg.info, proto.info) - - -def convert_proto_to_bosdyn_msgs_region_information(proto: "bosdyn.api.graph_nav.area_callback_pb2.RegionInformation", ros_msg: "bosdyn_msgs.msgs.RegionInformation") -> None: - ros_msg.region_id = proto.region_id - ros_msg.description = proto.description - convert_proto_to_bosdyn_msgs_route(proto.route, ros_msg.route) - ros_msg.route_is_set = proto.HasField("route") - - -def convert_bosdyn_msgs_region_information_to_proto(ros_msg: "bosdyn_msgs.msgs.RegionInformation", proto: "bosdyn.api.graph_nav.area_callback_pb2.RegionInformation") -> None: - proto.Clear() - proto.region_id = ros_msg.region_id - proto.description = ros_msg.description - if ros_msg.route_is_set: - convert_bosdyn_msgs_route_to_proto(ros_msg.route, proto.route) - - -def convert_proto_to_bosdyn_msgs_begin_callback_request(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackRequest", ros_msg: "bosdyn_msgs.msgs.BeginCallbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_region_information(proto.region_info, ros_msg.region_info) - ros_msg.region_info_is_set = proto.HasField("region_info") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - convert_proto_to_bosdyn_msgs_area_callback_data(proto.recorded_data, ros_msg.recorded_data) - ros_msg.recorded_data_is_set = proto.HasField("recorded_data") - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_begin_callback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginCallbackRequest", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.region_info_is_set: - convert_bosdyn_msgs_region_information_to_proto(ros_msg.region_info, proto.region_info) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - if ros_msg.recorded_data_is_set: - convert_bosdyn_msgs_area_callback_data_to_proto(ros_msg.recorded_data, proto.recorded_data) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_begin_callback_response_status(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.BeginCallbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_begin_callback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginCallbackResponseStatus", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_begin_callback_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackResponse", ros_msg: "bosdyn_msgs.msgs.BeginCallbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.command_id = proto.command_id - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - - -def convert_bosdyn_msgs_begin_callback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginCallbackResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginCallbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.command_id = ros_msg.command_id - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - - -def convert_proto_to_bosdyn_msgs_begin_control_request(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlRequest", ros_msg: "bosdyn_msgs.msgs.BeginControlRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_begin_control_request_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginControlRequest", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_begin_control_response_status(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlResponse.Status", ros_msg: "bosdyn_msgs.msgs.BeginControlResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_begin_control_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginControlResponseStatus", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_begin_control_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlResponse", ros_msg: "bosdyn_msgs.msgs.BeginControlResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_begin_control_response_to_proto(ros_msg: "bosdyn_msgs.msgs.BeginControlResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.BeginControlResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_update_callback_request_stage(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackRequest.Stage", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackRequestStage") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_request_stage_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackRequestStage", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackRequest.Stage") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_callback_request(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackRequest", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.command_id = proto.command_id - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.stage.value = proto.stage - - -def convert_bosdyn_msgs_update_callback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackRequest", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.command_id = ros_msg.command_id - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.stage = ros_msg.stage.value - - -def convert_proto_to_bosdyn_msgs_update_callback_response_status(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseStatus", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_callback_response_one_of_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseOneOfResponse") -> None: - if proto.HasField("policy"): - ros_msg.response_choice = ros_msg.RESPONSE_POLICY_SET - convert_proto_to_bosdyn_msgs_update_callback_response_nav_policy(proto.policy, ros_msg.policy) - if proto.HasField("error"): - ros_msg.response_choice = ros_msg.RESPONSE_ERROR_SET - convert_proto_to_bosdyn_msgs_update_callback_response_error(proto.error, ros_msg.error) - if proto.HasField("complete"): - ros_msg.response_choice = ros_msg.RESPONSE_COMPLETE_SET - convert_proto_to_bosdyn_msgs_update_callback_response_complete(proto.complete, ros_msg.complete) - - -def convert_bosdyn_msgs_update_callback_response_one_of_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseOneOfResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse") -> None: - proto.ClearField("response") - if ros_msg.response_choice == ros_msg.RESPONSE_POLICY_SET: - convert_bosdyn_msgs_update_callback_response_nav_policy_to_proto(ros_msg.policy, proto.policy) - if ros_msg.response_choice == ros_msg.RESPONSE_ERROR_SET: - convert_bosdyn_msgs_update_callback_response_error_to_proto(ros_msg.error, proto.error) - if ros_msg.response_choice == ros_msg.RESPONSE_COMPLETE_SET: - convert_bosdyn_msgs_update_callback_response_complete_to_proto(ros_msg.complete, proto.complete) - - -def convert_proto_to_bosdyn_msgs_update_callback_response_update_localization_localization_change(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.UpdateLocalization.LocalizationChange", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseUpdateLocalizationLocalizationChange") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_response_update_localization_localization_change_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseUpdateLocalizationLocalizationChange", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.UpdateLocalization.LocalizationChange") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_callback_response_update_localization(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.UpdateLocalization", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseUpdateLocalization") -> None: - ros_msg.change.value = proto.change - - -def convert_bosdyn_msgs_update_callback_response_update_localization_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseUpdateLocalization", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.UpdateLocalization") -> None: - proto.Clear() - proto.change = ros_msg.change.value - - -def convert_proto_to_bosdyn_msgs_update_callback_response_nav_policy_option(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.NavPolicy.Option", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseNavPolicyOption") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_response_nav_policy_option_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseNavPolicyOption", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.NavPolicy.Option") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_callback_response_nav_policy(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.NavPolicy", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseNavPolicy") -> None: - ros_msg.at_start.value = proto.at_start - ros_msg.at_end.value = proto.at_end - - -def convert_bosdyn_msgs_update_callback_response_nav_policy_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseNavPolicy", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.NavPolicy") -> None: - proto.Clear() - proto.at_start = ros_msg.at_start.value - proto.at_end = ros_msg.at_end.value - - -def convert_proto_to_bosdyn_msgs_update_callback_response_error_error_type(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Error.ErrorType", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseErrorErrorType") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_response_error_error_type_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseErrorErrorType", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Error.ErrorType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_callback_response_error(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Error", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseError") -> None: - ros_msg.error.value = proto.error - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - - -def convert_bosdyn_msgs_update_callback_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseError", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Error") -> None: - proto.Clear() - proto.error = ros_msg.error.value - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - - -def convert_proto_to_bosdyn_msgs_update_callback_response_complete(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Complete", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseComplete") -> None: - pass - - -def convert_bosdyn_msgs_update_callback_response_complete_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponseComplete", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse.Complete") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_update_callback_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse", ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_update_callback_response_one_of_response(proto, ros_msg.response) - convert_proto_to_bosdyn_msgs_update_callback_response_update_localization(proto.localization, ros_msg.localization) - ros_msg.localization_is_set = proto.HasField("localization") - - -def convert_bosdyn_msgs_update_callback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateCallbackResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.UpdateCallbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - convert_bosdyn_msgs_update_callback_response_one_of_response_to_proto(ros_msg.response, proto) - if ros_msg.localization_is_set: - convert_bosdyn_msgs_update_callback_response_update_localization_to_proto(ros_msg.localization, proto.localization) - - -def convert_proto_to_bosdyn_msgs_end_callback_request(proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackRequest", ros_msg: "bosdyn_msgs.msgs.EndCallbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_end_callback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.EndCallbackRequest", proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_end_callback_response_status(proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.EndCallbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_end_callback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.EndCallbackResponseStatus", proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_end_callback_response(proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackResponse", ros_msg: "bosdyn_msgs.msgs.EndCallbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_end_callback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.EndCallbackResponse", proto: "bosdyn.api.graph_nav.area_callback_pb2.EndCallbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_area_callback_data(proto: "bosdyn.api.graph_nav.area_callback_data_pb2.AreaCallbackData", ros_msg: "bosdyn_msgs.msgs.AreaCallbackData") -> None: - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_area_callback_data_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackData", proto: "bosdyn.api.graph_nav.area_callback_data_pb2.AreaCallbackData") -> None: - proto.Clear() - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_visual_refinement_options(proto: "bosdyn.api.graph_nav.graph_nav_pb2.VisualRefinementOptions", ros_msg: "bosdyn_msgs.msgs.VisualRefinementOptions") -> None: - ros_msg.verify_refinement_quality = proto.verify_refinement_quality - - -def convert_bosdyn_msgs_visual_refinement_options_to_proto(ros_msg: "bosdyn_msgs.msgs.VisualRefinementOptions", proto: "bosdyn.api.graph_nav.graph_nav_pb2.VisualRefinementOptions") -> None: - proto.Clear() - proto.verify_refinement_quality = ros_msg.verify_refinement_quality - - -def convert_proto_to_bosdyn_msgs_set_localization_request_fiducial_init(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest.FiducialInit", ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequestFiducialInit") -> None: - pass - - -def convert_bosdyn_msgs_set_localization_request_fiducial_init_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequestFiducialInit", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest.FiducialInit") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_set_localization_request_one_of_refinement(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest", ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequestOneOfRefinement") -> None: - if proto.HasField("refine_fiducial_result_with_icp"): - ros_msg.refinement_choice = ros_msg.REFINEMENT_REFINE_FIDUCIAL_RESULT_WITH_ICP_SET - ros_msg.refine_fiducial_result_with_icp = proto.refine_fiducial_result_with_icp - if proto.HasField("refine_with_visual_features"): - ros_msg.refinement_choice = ros_msg.REFINEMENT_REFINE_WITH_VISUAL_FEATURES_SET - convert_proto_to_bosdyn_msgs_visual_refinement_options(proto.refine_with_visual_features, ros_msg.refine_with_visual_features) - - -def convert_bosdyn_msgs_set_localization_request_one_of_refinement_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequestOneOfRefinement", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest") -> None: - proto.ClearField("refinement") - if ros_msg.refinement_choice == ros_msg.REFINEMENT_REFINE_FIDUCIAL_RESULT_WITH_ICP_SET: - proto.refine_fiducial_result_with_icp = ros_msg.refine_fiducial_result_with_icp - if ros_msg.refinement_choice == ros_msg.REFINEMENT_REFINE_WITH_VISUAL_FEATURES_SET: - convert_bosdyn_msgs_visual_refinement_options_to_proto(ros_msg.refine_with_visual_features, proto.refine_with_visual_features) - - -def convert_proto_to_bosdyn_msgs_set_localization_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest", ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_localization(proto.initial_guess, ros_msg.initial_guess) - ros_msg.initial_guess_is_set = proto.HasField("initial_guess") - convert_proto_to_geometry_msgs_pose(proto.ko_tform_body, ros_msg.ko_tform_body) - ros_msg.ko_tform_body_is_set = proto.HasField("ko_tform_body") - ros_msg.max_distance = proto.max_distance - ros_msg.max_yaw = proto.max_yaw - ros_msg.fiducial_init.value = proto.fiducial_init - ros_msg.use_fiducial_id = proto.use_fiducial_id - ros_msg.do_ambiguity_check = proto.do_ambiguity_check - ros_msg.restrict_fiducial_detections_to_target_waypoint = proto.restrict_fiducial_detections_to_target_waypoint - convert_proto_to_bosdyn_msgs_set_localization_request_one_of_refinement(proto, ros_msg.refinement) - - -def convert_bosdyn_msgs_set_localization_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.initial_guess_is_set: - convert_bosdyn_msgs_localization_to_proto(ros_msg.initial_guess, proto.initial_guess) - if ros_msg.ko_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.ko_tform_body, proto.ko_tform_body) - proto.max_distance = ros_msg.max_distance - proto.max_yaw = ros_msg.max_yaw - proto.fiducial_init = ros_msg.fiducial_init.value - proto.use_fiducial_id = ros_msg.use_fiducial_id - proto.do_ambiguity_check = ros_msg.do_ambiguity_check - proto.restrict_fiducial_detections_to_target_waypoint = ros_msg.restrict_fiducial_detections_to_target_waypoint - convert_bosdyn_msgs_set_localization_request_one_of_refinement_to_proto(ros_msg.refinement, proto) - - -def convert_proto_to_bosdyn_msgs_sensor_compatibility_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SensorCompatibilityStatus", ros_msg: "bosdyn_msgs.msgs.SensorCompatibilityStatus") -> None: - ros_msg.map_has_lidar_data = proto.map_has_lidar_data - ros_msg.robot_configured_for_lidar = proto.robot_configured_for_lidar - - -def convert_bosdyn_msgs_sensor_compatibility_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SensorCompatibilityStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SensorCompatibilityStatus") -> None: - proto.Clear() - proto.map_has_lidar_data = ros_msg.map_has_lidar_data - proto.robot_configured_for_lidar = ros_msg.robot_configured_for_lidar - - -def convert_proto_to_bosdyn_msgs_set_localization_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.Status", ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_set_localization_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_set_localization_response_suspected_ambiguity(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.SuspectedAmbiguity", ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseSuspectedAmbiguity") -> None: - convert_proto_to_geometry_msgs_pose(proto.alternate_robot_tform_waypoint, ros_msg.alternate_robot_tform_waypoint) - ros_msg.alternate_robot_tform_waypoint_is_set = proto.HasField("alternate_robot_tform_waypoint") - - -def convert_bosdyn_msgs_set_localization_response_suspected_ambiguity_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseSuspectedAmbiguity", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.SuspectedAmbiguity") -> None: - proto.Clear() - if ros_msg.alternate_robot_tform_waypoint_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.alternate_robot_tform_waypoint, proto.alternate_robot_tform_waypoint) - - -def convert_proto_to_bosdyn_msgs_set_localization_response_quality_check_result(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.QualityCheckResult", ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseQualityCheckResult") -> None: - pass - - -def convert_bosdyn_msgs_set_localization_response_quality_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponseQualityCheckResult", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse.QualityCheckResult") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_set_localization_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse", ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.error_report = proto.error_report - convert_proto_to_bosdyn_msgs_localization(proto.localization, ros_msg.localization) - ros_msg.localization_is_set = proto.HasField("localization") - convert_proto_to_bosdyn_msgs_set_localization_response_suspected_ambiguity(proto.suspected_ambiguity, ros_msg.suspected_ambiguity) - ros_msg.suspected_ambiguity_is_set = proto.HasField("suspected_ambiguity") - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - convert_proto_to_bosdyn_msgs_sensor_compatibility_status(proto.sensor_status, ros_msg.sensor_status) - ros_msg.sensor_status_is_set = proto.HasField("sensor_status") - ros_msg.quality_check_result.value = proto.quality_check_result - - -def convert_bosdyn_msgs_set_localization_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLocalizationResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.SetLocalizationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.error_report = ros_msg.error_report - if ros_msg.localization_is_set: - convert_bosdyn_msgs_localization_to_proto(ros_msg.localization, proto.localization) - if ros_msg.suspected_ambiguity_is_set: - convert_bosdyn_msgs_set_localization_response_suspected_ambiguity_to_proto(ros_msg.suspected_ambiguity, proto.suspected_ambiguity) - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - if ros_msg.sensor_status_is_set: - convert_bosdyn_msgs_sensor_compatibility_status_to_proto(ros_msg.sensor_status, proto.sensor_status) - proto.quality_check_result = ros_msg.quality_check_result.value - - -def convert_proto_to_bosdyn_msgs_route_gen_params(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteGenParams", ros_msg: "bosdyn_msgs.msgs.RouteGenParams") -> None: - pass - - -def convert_bosdyn_msgs_route_gen_params_to_proto(ros_msg: "bosdyn_msgs.msgs.RouteGenParams", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteGenParams") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_travel_params_feature_quality_tolerance(proto: "bosdyn.api.graph_nav.graph_nav_pb2.TravelParams.FeatureQualityTolerance", ros_msg: "bosdyn_msgs.msgs.TravelParamsFeatureQualityTolerance") -> None: - pass - - -def convert_bosdyn_msgs_travel_params_feature_quality_tolerance_to_proto(ros_msg: "bosdyn_msgs.msgs.TravelParamsFeatureQualityTolerance", proto: "bosdyn.api.graph_nav.graph_nav_pb2.TravelParams.FeatureQualityTolerance") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_travel_params(proto: "bosdyn.api.graph_nav.graph_nav_pb2.TravelParams", ros_msg: "bosdyn_msgs.msgs.TravelParams") -> None: - ros_msg.max_distance = proto.max_distance - ros_msg.max_yaw = proto.max_yaw - convert_proto_to_bosdyn_msgs_se2_velocity_limit(proto.velocity_limit, ros_msg.velocity_limit) - ros_msg.velocity_limit_is_set = proto.HasField("velocity_limit") - ros_msg.ignore_final_yaw = proto.ignore_final_yaw - ros_msg.feature_quality_tolerance.value = proto.feature_quality_tolerance - ros_msg.disable_directed_exploration = proto.disable_directed_exploration - ros_msg.disable_alternate_route_finding = proto.disable_alternate_route_finding - ros_msg.path_following_mode.value = proto.path_following_mode - convert_proto_to_builtin_interfaces_duration(proto.blocked_path_wait_time, ros_msg.blocked_path_wait_time) - ros_msg.blocked_path_wait_time_is_set = proto.HasField("blocked_path_wait_time") - ros_msg.ground_clutter_mode.value = proto.ground_clutter_mode - - -def convert_bosdyn_msgs_travel_params_to_proto(ros_msg: "bosdyn_msgs.msgs.TravelParams", proto: "bosdyn.api.graph_nav.graph_nav_pb2.TravelParams") -> None: - proto.Clear() - proto.max_distance = ros_msg.max_distance - proto.max_yaw = ros_msg.max_yaw - if ros_msg.velocity_limit_is_set: - convert_bosdyn_msgs_se2_velocity_limit_to_proto(ros_msg.velocity_limit, proto.velocity_limit) - proto.ignore_final_yaw = ros_msg.ignore_final_yaw - proto.feature_quality_tolerance = ros_msg.feature_quality_tolerance.value - proto.disable_directed_exploration = ros_msg.disable_directed_exploration - proto.disable_alternate_route_finding = ros_msg.disable_alternate_route_finding - proto.path_following_mode = ros_msg.path_following_mode.value - if ros_msg.blocked_path_wait_time_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.blocked_path_wait_time, proto.blocked_path_wait_time) - proto.ground_clutter_mode = ros_msg.ground_clutter_mode.value - - -def convert_proto_to_bosdyn_msgs_modify_navigation_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ModifyNavigationResponse.Status", ros_msg: "bosdyn_msgs.msgs.ModifyNavigationResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_modify_navigation_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ModifyNavigationResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ModifyNavigationResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_modify_navigation_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ModifyNavigationResponse", ros_msg: "bosdyn_msgs.msgs.ModifyNavigationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_modify_navigation_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ModifyNavigationResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ModifyNavigationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_navigate_to_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToRequest", ros_msg: "bosdyn_msgs.msgs.NavigateToRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - ros_msg.destination_waypoint_id = proto.destination_waypoint_id - convert_proto_to_bosdyn_msgs_route_gen_params(proto.route_params, ros_msg.route_params) - ros_msg.route_params_is_set = proto.HasField("route_params") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.clock_identifier = proto.clock_identifier - convert_proto_to_bosdyn_msgs_se2_pose(proto.destination_waypoint_tform_body_goal, ros_msg.destination_waypoint_tform_body_goal) - ros_msg.destination_waypoint_tform_body_goal_is_set = proto.HasField("destination_waypoint_tform_body_goal") - ros_msg.command_id = proto.command_id - ros_msg.route_blocked_behavior.value = proto.route_blocked_behavior - - -def convert_bosdyn_msgs_navigate_to_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - proto.destination_waypoint_id = ros_msg.destination_waypoint_id - if ros_msg.route_params_is_set: - convert_bosdyn_msgs_route_gen_params_to_proto(ros_msg.route_params, proto.route_params) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.clock_identifier = ros_msg.clock_identifier - if ros_msg.destination_waypoint_tform_body_goal_is_set: - convert_bosdyn_msgs_se2_pose_to_proto(ros_msg.destination_waypoint_tform_body_goal, proto.destination_waypoint_tform_body_goal) - proto.command_id = ros_msg.command_id - proto.route_blocked_behavior = ros_msg.route_blocked_behavior.value - - -def convert_proto_to_bosdyn_msgs_navigate_to_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToResponse.Status", ros_msg: "bosdyn_msgs.msgs.NavigateToResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigate_to_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigate_to_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToResponse", ros_msg: "bosdyn_msgs.msgs.NavigateToResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - ros_msg.command_id = proto.command_id - ros_msg.error_waypoint_ids = [] - for _item in proto.error_waypoint_ids: - ros_msg.error_waypoint_ids.append(_item) - convert_proto_to_bosdyn_msgs_area_callback_service_error(proto.area_callback_error, ros_msg.area_callback_error) - ros_msg.area_callback_error_is_set = proto.HasField("area_callback_error") - - -def convert_bosdyn_msgs_navigate_to_response_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - proto.status = ros_msg.status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - proto.command_id = ros_msg.command_id - del proto.error_waypoint_ids[:] - for _item in ros_msg.error_waypoint_ids: - proto.error_waypoint_ids.append(_item) - if ros_msg.area_callback_error_is_set: - convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg.area_callback_error, proto.area_callback_error) - - -def convert_proto_to_bosdyn_msgs_route_following_params_start_route_behavior(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.StartRouteBehavior", ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsStartRouteBehavior") -> None: - pass - - -def convert_bosdyn_msgs_route_following_params_start_route_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsStartRouteBehavior", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.StartRouteBehavior") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_route_following_params_resume_behavior(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.ResumeBehavior", ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsResumeBehavior") -> None: - pass - - -def convert_bosdyn_msgs_route_following_params_resume_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsResumeBehavior", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.ResumeBehavior") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_route_following_params_route_blocked_behavior(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.RouteBlockedBehavior", ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsRouteBlockedBehavior") -> None: - pass - - -def convert_bosdyn_msgs_route_following_params_route_blocked_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.RouteFollowingParamsRouteBlockedBehavior", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams.RouteBlockedBehavior") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_route_following_params(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams", ros_msg: "bosdyn_msgs.msgs.RouteFollowingParams") -> None: - ros_msg.new_cmd_behavior.value = proto.new_cmd_behavior - ros_msg.existing_cmd_behavior.value = proto.existing_cmd_behavior - ros_msg.route_blocked_behavior.value = proto.route_blocked_behavior - - -def convert_bosdyn_msgs_route_following_params_to_proto(ros_msg: "bosdyn_msgs.msgs.RouteFollowingParams", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RouteFollowingParams") -> None: - proto.Clear() - proto.new_cmd_behavior = ros_msg.new_cmd_behavior.value - proto.existing_cmd_behavior = ros_msg.existing_cmd_behavior.value - proto.route_blocked_behavior = ros_msg.route_blocked_behavior.value - - -def convert_proto_to_bosdyn_msgs_navigate_route_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteRequest", ros_msg: "bosdyn_msgs.msgs.NavigateRouteRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_route(proto.route, ros_msg.route) - ros_msg.route_is_set = proto.HasField("route") - convert_proto_to_bosdyn_msgs_route_following_params(proto.route_follow_params, ros_msg.route_follow_params) - ros_msg.route_follow_params_is_set = proto.HasField("route_follow_params") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.clock_identifier = proto.clock_identifier - convert_proto_to_bosdyn_msgs_se2_pose(proto.destination_waypoint_tform_body_goal, ros_msg.destination_waypoint_tform_body_goal) - ros_msg.destination_waypoint_tform_body_goal_is_set = proto.HasField("destination_waypoint_tform_body_goal") - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_navigate_route_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateRouteRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.route_is_set: - convert_bosdyn_msgs_route_to_proto(ros_msg.route, proto.route) - if ros_msg.route_follow_params_is_set: - convert_bosdyn_msgs_route_following_params_to_proto(ros_msg.route_follow_params, proto.route_follow_params) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.clock_identifier = ros_msg.clock_identifier - if ros_msg.destination_waypoint_tform_body_goal_is_set: - convert_bosdyn_msgs_se2_pose_to_proto(ros_msg.destination_waypoint_tform_body_goal, proto.destination_waypoint_tform_body_goal) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_navigate_route_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteResponse.Status", ros_msg: "bosdyn_msgs.msgs.NavigateRouteResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigate_route_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateRouteResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigate_route_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteResponse", ros_msg: "bosdyn_msgs.msgs.NavigateRouteResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - ros_msg.command_id = proto.command_id - ros_msg.error_waypoint_ids = [] - for _item in proto.error_waypoint_ids: - ros_msg.error_waypoint_ids.append(_item) - from bosdyn_msgs.msg import EdgeId - ros_msg.error_edge_ids = [] - for _item in proto.error_edge_ids: - ros_msg.error_edge_ids.append(EdgeId()) - convert_proto_to_bosdyn_msgs_edge_id(_item, ros_msg.error_edge_ids[-1]) - convert_proto_to_bosdyn_msgs_area_callback_service_error(proto.area_callback_error, ros_msg.area_callback_error) - ros_msg.area_callback_error_is_set = proto.HasField("area_callback_error") - - -def convert_bosdyn_msgs_navigate_route_response_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateRouteResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateRouteResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - proto.status = ros_msg.status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - proto.command_id = ros_msg.command_id - del proto.error_waypoint_ids[:] - for _item in ros_msg.error_waypoint_ids: - proto.error_waypoint_ids.append(_item) - del proto.error_edge_ids[:] - for _item in ros_msg.error_edge_ids: - convert_bosdyn_msgs_edge_id_to_proto(_item, proto.error_edge_ids.add()) - if ros_msg.area_callback_error_is_set: - convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg.area_callback_error, proto.area_callback_error) - - -def convert_proto_to_bosdyn_msgs_navigate_to_anchor_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorRequest", ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_geometry_msgs_pose(proto.seed_tform_goal, ros_msg.seed_tform_goal) - ros_msg.seed_tform_goal_is_set = proto.HasField("seed_tform_goal") - convert_proto_to_geometry_msgs_vector3(proto.goal_waypoint_rt_seed_ewrt_seed_tolerance, ros_msg.goal_waypoint_rt_seed_ewrt_seed_tolerance) - ros_msg.goal_waypoint_rt_seed_ewrt_seed_tolerance_is_set = proto.HasField("goal_waypoint_rt_seed_ewrt_seed_tolerance") - convert_proto_to_bosdyn_msgs_route_gen_params(proto.route_params, ros_msg.route_params) - ros_msg.route_params_is_set = proto.HasField("route_params") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - ros_msg.clock_identifier = proto.clock_identifier - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_navigate_to_anchor_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.seed_tform_goal_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.seed_tform_goal, proto.seed_tform_goal) - if ros_msg.goal_waypoint_rt_seed_ewrt_seed_tolerance_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.goal_waypoint_rt_seed_ewrt_seed_tolerance, proto.goal_waypoint_rt_seed_ewrt_seed_tolerance) - if ros_msg.route_params_is_set: - convert_bosdyn_msgs_route_gen_params_to_proto(ros_msg.route_params, proto.route_params) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - proto.clock_identifier = ros_msg.clock_identifier - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_navigate_to_anchor_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorResponse.Status", ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigate_to_anchor_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigate_to_anchor_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorResponse", ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - ros_msg.command_id = proto.command_id - ros_msg.error_waypoint_ids = [] - for _item in proto.error_waypoint_ids: - ros_msg.error_waypoint_ids.append(_item) - convert_proto_to_bosdyn_msgs_area_callback_service_error(proto.area_callback_error, ros_msg.area_callback_error) - ros_msg.area_callback_error_is_set = proto.HasField("area_callback_error") - - -def convert_bosdyn_msgs_navigate_to_anchor_response_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigateToAnchorResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigateToAnchorResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - proto.status = ros_msg.status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - proto.command_id = ros_msg.command_id - del proto.error_waypoint_ids[:] - for _item in ros_msg.error_waypoint_ids: - proto.error_waypoint_ids.append(_item) - if ros_msg.area_callback_error_is_set: - convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg.area_callback_error, proto.area_callback_error) - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_navigation_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigation_feedback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_active_region_information_area_callback_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.ActiveRegionInformation.AreaCallbackStatus", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseActiveRegionInformationAreaCallbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigation_feedback_response_active_region_information_area_callback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseActiveRegionInformationAreaCallbackStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.ActiveRegionInformation.AreaCallbackStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_active_region_information(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.ActiveRegionInformation", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseActiveRegionInformation") -> None: - ros_msg.description = proto.description - ros_msg.service_name = proto.service_name - ros_msg.region_status.value = proto.region_status - - -def convert_bosdyn_msgs_navigation_feedback_response_active_region_information_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseActiveRegionInformation", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.ActiveRegionInformation") -> None: - proto.Clear() - proto.description = ros_msg.description - proto.service_name = ros_msg.service_name - proto.region_status = ros_msg.region_status.value - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_route_following_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.RouteFollowingStatus", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseRouteFollowingStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigation_feedback_response_route_following_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseRouteFollowingStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.RouteFollowingStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_blockage_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.BlockageStatus", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseBlockageStatus") -> None: - pass - - -def convert_bosdyn_msgs_navigation_feedback_response_blockage_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseBlockageStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.BlockageStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response_stuck_reason(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.StuckReason", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseStuckReason") -> None: - pass - - -def convert_bosdyn_msgs_navigation_feedback_response_stuck_reason_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponseStuckReason", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse.StuckReason") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_navigation_feedback_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsAreaCallbackError - ros_msg.area_callback_errors = [] - for _item in proto.area_callback_errors: - ros_msg.area_callback_errors.append(KeyStringValueBosdynMsgsAreaCallbackError()) - ros_msg.area_callback_errors[-1].key = _item - convert_proto_to_bosdyn_msgs_area_callback_error(proto.area_callback_errors[_item], ros_msg.area_callback_errors[-1].value) - convert_proto_to_bosdyn_msgs_route(proto.remaining_route, ros_msg.remaining_route) - ros_msg.remaining_route_is_set = proto.HasField("remaining_route") - ros_msg.command_id = proto.command_id - convert_proto_to_geometry_msgs_pose(proto.last_ko_tform_goal, ros_msg.last_ko_tform_goal) - ros_msg.last_ko_tform_goal_is_set = proto.HasField("last_ko_tform_goal") - ros_msg.body_movement_status.value = proto.body_movement_status - ros_msg.path_following_mode.value = proto.path_following_mode - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsNavigationFeedbackResponseActiveRegionInformation - ros_msg.active_region_information = [] - for _item in proto.active_region_information: - ros_msg.active_region_information.append(KeyStringValueBosdynMsgsNavigationFeedbackResponseActiveRegionInformation()) - ros_msg.active_region_information[-1].key = _item - convert_proto_to_bosdyn_msgs_navigation_feedback_response_active_region_information(proto.active_region_information[_item], ros_msg.active_region_information[-1].value) - ros_msg.route_following_status.value = proto.route_following_status - ros_msg.blockage_status.value = proto.blockage_status - ros_msg.stuck_reason.value = proto.stuck_reason - - -def convert_bosdyn_msgs_navigation_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.NavigationFeedbackResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.NavigationFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - for _item in ros_msg.area_callback_errors: - convert_bosdyn_msgs_area_callback_error_to_proto(_item.value, proto.area_callback_errors[_item.key]) - if ros_msg.remaining_route_is_set: - convert_bosdyn_msgs_route_to_proto(ros_msg.remaining_route, proto.remaining_route) - proto.command_id = ros_msg.command_id - if ros_msg.last_ko_tform_goal_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.last_ko_tform_goal, proto.last_ko_tform_goal) - proto.body_movement_status = ros_msg.body_movement_status.value - proto.path_following_mode = ros_msg.path_following_mode.value - for _item in ros_msg.active_region_information: - convert_bosdyn_msgs_navigation_feedback_response_active_region_information_to_proto(_item.value, proto.active_region_information[_item.key]) - proto.route_following_status = ros_msg.route_following_status.value - proto.blockage_status = ros_msg.blockage_status.value - proto.stuck_reason = ros_msg.stuck_reason.value - - -def convert_proto_to_bosdyn_msgs_get_localization_state_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.GetLocalizationStateRequest", ros_msg: "bosdyn_msgs.msgs.GetLocalizationStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.waypoint_id = proto.waypoint_id - ros_msg.request_live_point_cloud = proto.request_live_point_cloud - ros_msg.request_live_images = proto.request_live_images - ros_msg.request_live_terrain_maps = proto.request_live_terrain_maps - ros_msg.request_live_world_objects = proto.request_live_world_objects - ros_msg.request_live_robot_state = proto.request_live_robot_state - ros_msg.compress_live_point_cloud = proto.compress_live_point_cloud - - -def convert_bosdyn_msgs_get_localization_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalizationStateRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.GetLocalizationStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.waypoint_id = ros_msg.waypoint_id - proto.request_live_point_cloud = ros_msg.request_live_point_cloud - proto.request_live_images = ros_msg.request_live_images - proto.request_live_terrain_maps = ros_msg.request_live_terrain_maps - proto.request_live_world_objects = ros_msg.request_live_world_objects - proto.request_live_robot_state = ros_msg.request_live_robot_state - proto.compress_live_point_cloud = ros_msg.compress_live_point_cloud - - -def convert_proto_to_bosdyn_msgs_remote_point_cloud_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.RemotePointCloudStatus", ros_msg: "bosdyn_msgs.msgs.RemotePointCloudStatus") -> None: - ros_msg.service_name = proto.service_name - ros_msg.exists_in_directory = proto.exists_in_directory - ros_msg.has_data = proto.has_data - - -def convert_bosdyn_msgs_remote_point_cloud_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RemotePointCloudStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.RemotePointCloudStatus") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.exists_in_directory = ros_msg.exists_in_directory - proto.has_data = ros_msg.has_data - - -def convert_proto_to_bosdyn_msgs_lost_detector_state(proto: "bosdyn.api.graph_nav.graph_nav_pb2.LostDetectorState", ros_msg: "bosdyn_msgs.msgs.LostDetectorState") -> None: - ros_msg.is_lost = proto.is_lost - - -def convert_bosdyn_msgs_lost_detector_state_to_proto(ros_msg: "bosdyn_msgs.msgs.LostDetectorState", proto: "bosdyn.api.graph_nav.graph_nav_pb2.LostDetectorState") -> None: - proto.Clear() - proto.is_lost = ros_msg.is_lost - - -def convert_proto_to_bosdyn_msgs_get_localization_state_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.GetLocalizationStateResponse", ros_msg: "bosdyn_msgs.msgs.GetLocalizationStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_localization(proto.localization, ros_msg.localization) - ros_msg.localization_is_set = proto.HasField("localization") - convert_proto_to_bosdyn_msgs_kinematic_state(proto.robot_kinematics, ros_msg.robot_kinematics) - ros_msg.robot_kinematics_is_set = proto.HasField("robot_kinematics") - from bosdyn_msgs.msg import RemotePointCloudStatus - ros_msg.remote_cloud_status = [] - for _item in proto.remote_cloud_status: - ros_msg.remote_cloud_status.append(RemotePointCloudStatus()) - convert_proto_to_bosdyn_msgs_remote_point_cloud_status(_item, ros_msg.remote_cloud_status[-1]) - convert_proto_to_bosdyn_msgs_waypoint_snapshot(proto.live_data, ros_msg.live_data) - ros_msg.live_data_is_set = proto.HasField("live_data") - convert_proto_to_bosdyn_msgs_lost_detector_state(proto.lost_detector_state, ros_msg.lost_detector_state) - ros_msg.lost_detector_state_is_set = proto.HasField("lost_detector_state") - - -def convert_bosdyn_msgs_get_localization_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalizationStateResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.GetLocalizationStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.localization_is_set: - convert_bosdyn_msgs_localization_to_proto(ros_msg.localization, proto.localization) - if ros_msg.robot_kinematics_is_set: - convert_bosdyn_msgs_kinematic_state_to_proto(ros_msg.robot_kinematics, proto.robot_kinematics) - del proto.remote_cloud_status[:] - for _item in ros_msg.remote_cloud_status: - convert_bosdyn_msgs_remote_point_cloud_status_to_proto(_item, proto.remote_cloud_status.add()) - if ros_msg.live_data_is_set: - convert_bosdyn_msgs_waypoint_snapshot_to_proto(ros_msg.live_data, proto.live_data) - if ros_msg.lost_detector_state_is_set: - convert_bosdyn_msgs_lost_detector_state_to_proto(ros_msg.lost_detector_state, proto.lost_detector_state) - - -def convert_proto_to_bosdyn_msgs_clear_graph_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphRequest", ros_msg: "bosdyn_msgs.msgs.ClearGraphRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_clear_graph_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearGraphRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_clear_graph_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphResponse.Status", ros_msg: "bosdyn_msgs.msgs.ClearGraphResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_clear_graph_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearGraphResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_clear_graph_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphResponse", ros_msg: "bosdyn_msgs.msgs.ClearGraphResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_clear_graph_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearGraphResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ClearGraphResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_upload_graph_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphRequest", ros_msg: "bosdyn_msgs.msgs.UploadGraphRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_graph(proto.graph, ros_msg.graph) - ros_msg.graph_is_set = proto.HasField("graph") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.generate_new_anchoring = proto.generate_new_anchoring - ros_msg.treat_validation_warnings_as_errors = proto.treat_validation_warnings_as_errors - - -def convert_bosdyn_msgs_upload_graph_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadGraphRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.graph_is_set: - convert_bosdyn_msgs_graph_to_proto(ros_msg.graph, proto.graph) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.generate_new_anchoring = ros_msg.generate_new_anchoring - proto.treat_validation_warnings_as_errors = ros_msg.treat_validation_warnings_as_errors - - -def convert_proto_to_bosdyn_msgs_upload_graph_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse.Status", ros_msg: "bosdyn_msgs.msgs.UploadGraphResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_upload_graph_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadGraphResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_upload_graph_response_validation_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse.ValidationStatus", ros_msg: "bosdyn_msgs.msgs.UploadGraphResponseValidationStatus") -> None: - ros_msg.missing_waypoint_ids_in_edges = [] - for _item in proto.missing_waypoint_ids_in_edges: - ros_msg.missing_waypoint_ids_in_edges.append(_item) - ros_msg.missing_waypoint_ids_in_anchors = [] - for _item in proto.missing_waypoint_ids_in_anchors: - ros_msg.missing_waypoint_ids_in_anchors.append(_item) - from bosdyn_msgs.msg import EdgeId - ros_msg.edge_ids_invalid_transform = [] - for _item in proto.edge_ids_invalid_transform: - ros_msg.edge_ids_invalid_transform.append(EdgeId()) - convert_proto_to_bosdyn_msgs_edge_id(_item, ros_msg.edge_ids_invalid_transform[-1]) - ros_msg.waypoint_anchors_invalid_transform = [] - for _item in proto.waypoint_anchors_invalid_transform: - ros_msg.waypoint_anchors_invalid_transform.append(_item) - ros_msg.object_anchors_invalid_transform = [] - for _item in proto.object_anchors_invalid_transform: - ros_msg.object_anchors_invalid_transform.append(_item) - ros_msg.duplicate_waypoint_ids = [] - for _item in proto.duplicate_waypoint_ids: - ros_msg.duplicate_waypoint_ids.append(_item) - ros_msg.duplicate_waypoint_anchor_ids = [] - for _item in proto.duplicate_waypoint_anchor_ids: - ros_msg.duplicate_waypoint_anchor_ids.append(_item) - ros_msg.duplicate_object_anchor_ids = [] - for _item in proto.duplicate_object_anchor_ids: - ros_msg.duplicate_object_anchor_ids.append(_item) - from bosdyn_msgs.msg import EdgeId - ros_msg.duplicate_edge_ids = [] - for _item in proto.duplicate_edge_ids: - ros_msg.duplicate_edge_ids.append(EdgeId()) - convert_proto_to_bosdyn_msgs_edge_id(_item, ros_msg.duplicate_edge_ids[-1]) - ros_msg.invalid_waypoint_ids_self_edges = [] - for _item in proto.invalid_waypoint_ids_self_edges: - ros_msg.invalid_waypoint_ids_self_edges.append(_item) - ros_msg.has_empty_waypoint_ids = proto.has_empty_waypoint_ids - ros_msg.has_empty_edge_ids = proto.has_empty_edge_ids - ros_msg.has_empty_waypoint_anchor_ids = proto.has_empty_waypoint_anchor_ids - ros_msg.has_empty_object_anchor_ids = proto.has_empty_object_anchor_ids - - -def convert_bosdyn_msgs_upload_graph_response_validation_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadGraphResponseValidationStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse.ValidationStatus") -> None: - proto.Clear() - del proto.missing_waypoint_ids_in_edges[:] - for _item in ros_msg.missing_waypoint_ids_in_edges: - proto.missing_waypoint_ids_in_edges.append(_item) - del proto.missing_waypoint_ids_in_anchors[:] - for _item in ros_msg.missing_waypoint_ids_in_anchors: - proto.missing_waypoint_ids_in_anchors.append(_item) - del proto.edge_ids_invalid_transform[:] - for _item in ros_msg.edge_ids_invalid_transform: - convert_bosdyn_msgs_edge_id_to_proto(_item, proto.edge_ids_invalid_transform.add()) - del proto.waypoint_anchors_invalid_transform[:] - for _item in ros_msg.waypoint_anchors_invalid_transform: - proto.waypoint_anchors_invalid_transform.append(_item) - del proto.object_anchors_invalid_transform[:] - for _item in ros_msg.object_anchors_invalid_transform: - proto.object_anchors_invalid_transform.append(_item) - del proto.duplicate_waypoint_ids[:] - for _item in ros_msg.duplicate_waypoint_ids: - proto.duplicate_waypoint_ids.append(_item) - del proto.duplicate_waypoint_anchor_ids[:] - for _item in ros_msg.duplicate_waypoint_anchor_ids: - proto.duplicate_waypoint_anchor_ids.append(_item) - del proto.duplicate_object_anchor_ids[:] - for _item in ros_msg.duplicate_object_anchor_ids: - proto.duplicate_object_anchor_ids.append(_item) - del proto.duplicate_edge_ids[:] - for _item in ros_msg.duplicate_edge_ids: - convert_bosdyn_msgs_edge_id_to_proto(_item, proto.duplicate_edge_ids.add()) - del proto.invalid_waypoint_ids_self_edges[:] - for _item in ros_msg.invalid_waypoint_ids_self_edges: - proto.invalid_waypoint_ids_self_edges.append(_item) - proto.has_empty_waypoint_ids = ros_msg.has_empty_waypoint_ids - proto.has_empty_edge_ids = ros_msg.has_empty_edge_ids - proto.has_empty_waypoint_anchor_ids = ros_msg.has_empty_waypoint_anchor_ids - proto.has_empty_object_anchor_ids = ros_msg.has_empty_object_anchor_ids - - -def convert_proto_to_bosdyn_msgs_upload_graph_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse", ros_msg: "bosdyn_msgs.msgs.UploadGraphResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.loaded_waypoint_snapshot_ids = [] - for _item in proto.loaded_waypoint_snapshot_ids: - ros_msg.loaded_waypoint_snapshot_ids.append(_item) - ros_msg.unknown_waypoint_snapshot_ids = [] - for _item in proto.unknown_waypoint_snapshot_ids: - ros_msg.unknown_waypoint_snapshot_ids.append(_item) - ros_msg.loaded_edge_snapshot_ids = [] - for _item in proto.loaded_edge_snapshot_ids: - ros_msg.loaded_edge_snapshot_ids.append(_item) - ros_msg.unknown_edge_snapshot_ids = [] - for _item in proto.unknown_edge_snapshot_ids: - ros_msg.unknown_edge_snapshot_ids.append(_item) - ros_msg.license_status.value = proto.license_status - convert_proto_to_bosdyn_msgs_sensor_compatibility_status(proto.sensor_status, ros_msg.sensor_status) - ros_msg.sensor_status_is_set = proto.HasField("sensor_status") - convert_proto_to_bosdyn_msgs_area_callback_service_error(proto.area_callback_error, ros_msg.area_callback_error) - ros_msg.area_callback_error_is_set = proto.HasField("area_callback_error") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - convert_proto_to_bosdyn_msgs_upload_graph_response_validation_status(proto.validation_status, ros_msg.validation_status) - ros_msg.validation_status_is_set = proto.HasField("validation_status") - - -def convert_bosdyn_msgs_upload_graph_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadGraphResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadGraphResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - del proto.loaded_waypoint_snapshot_ids[:] - for _item in ros_msg.loaded_waypoint_snapshot_ids: - proto.loaded_waypoint_snapshot_ids.append(_item) - del proto.unknown_waypoint_snapshot_ids[:] - for _item in ros_msg.unknown_waypoint_snapshot_ids: - proto.unknown_waypoint_snapshot_ids.append(_item) - del proto.loaded_edge_snapshot_ids[:] - for _item in ros_msg.loaded_edge_snapshot_ids: - proto.loaded_edge_snapshot_ids.append(_item) - del proto.unknown_edge_snapshot_ids[:] - for _item in ros_msg.unknown_edge_snapshot_ids: - proto.unknown_edge_snapshot_ids.append(_item) - proto.license_status = ros_msg.license_status.value - if ros_msg.sensor_status_is_set: - convert_bosdyn_msgs_sensor_compatibility_status_to_proto(ros_msg.sensor_status, proto.sensor_status) - if ros_msg.area_callback_error_is_set: - convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg.area_callback_error, proto.area_callback_error) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - if ros_msg.validation_status_is_set: - convert_bosdyn_msgs_upload_graph_response_validation_status_to_proto(ros_msg.validation_status, proto.validation_status) - - -def convert_proto_to_bosdyn_msgs_download_graph_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadGraphRequest", ros_msg: "bosdyn_msgs.msgs.DownloadGraphRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_download_graph_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadGraphRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadGraphRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_download_graph_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadGraphResponse", ros_msg: "bosdyn_msgs.msgs.DownloadGraphResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_graph(proto.graph, ros_msg.graph) - ros_msg.graph_is_set = proto.HasField("graph") - - -def convert_bosdyn_msgs_download_graph_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadGraphResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadGraphResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.graph_is_set: - convert_bosdyn_msgs_graph_to_proto(ros_msg.graph, proto.graph) - - -def convert_proto_to_bosdyn_msgs_upload_waypoint_snapshot_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotRequest", ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_chunk(proto.chunk, ros_msg.chunk) - ros_msg.chunk_is_set = proto.HasField("chunk") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_upload_waypoint_snapshot_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.chunk_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.chunk, proto.chunk) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_upload_waypoint_snapshot_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotResponse.Status", ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_upload_waypoint_snapshot_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_upload_waypoint_snapshot_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotResponse", ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_sensor_compatibility_status(proto.sensor_status, ros_msg.sensor_status) - ros_msg.sensor_status_is_set = proto.HasField("sensor_status") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_upload_waypoint_snapshot_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadWaypointSnapshotResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadWaypointSnapshotResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - if ros_msg.sensor_status_is_set: - convert_bosdyn_msgs_sensor_compatibility_status_to_proto(ros_msg.sensor_status, proto.sensor_status) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_upload_edge_snapshot_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadEdgeSnapshotRequest", ros_msg: "bosdyn_msgs.msgs.UploadEdgeSnapshotRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_chunk(proto.chunk, ros_msg.chunk) - ros_msg.chunk_is_set = proto.HasField("chunk") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_upload_edge_snapshot_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadEdgeSnapshotRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadEdgeSnapshotRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.chunk_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.chunk, proto.chunk) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_upload_edge_snapshot_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadEdgeSnapshotResponse", ros_msg: "bosdyn_msgs.msgs.UploadEdgeSnapshotResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_upload_edge_snapshot_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UploadEdgeSnapshotResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.UploadEdgeSnapshotResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_download_waypoint_snapshot_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotRequest", ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.waypoint_snapshot_id = proto.waypoint_snapshot_id - ros_msg.download_images = proto.download_images - ros_msg.compress_point_cloud = proto.compress_point_cloud - ros_msg.do_not_download_point_cloud = proto.do_not_download_point_cloud - - -def convert_bosdyn_msgs_download_waypoint_snapshot_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.waypoint_snapshot_id = ros_msg.waypoint_snapshot_id - proto.download_images = ros_msg.download_images - proto.compress_point_cloud = ros_msg.compress_point_cloud - proto.do_not_download_point_cloud = ros_msg.do_not_download_point_cloud - - -def convert_proto_to_bosdyn_msgs_download_waypoint_snapshot_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotResponse.Status", ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_download_waypoint_snapshot_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_download_waypoint_snapshot_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotResponse", ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.waypoint_snapshot_id = proto.waypoint_snapshot_id - convert_proto_to_bosdyn_msgs_data_chunk(proto.chunk, ros_msg.chunk) - ros_msg.chunk_is_set = proto.HasField("chunk") - - -def convert_bosdyn_msgs_download_waypoint_snapshot_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadWaypointSnapshotResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadWaypointSnapshotResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.waypoint_snapshot_id = ros_msg.waypoint_snapshot_id - if ros_msg.chunk_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.chunk, proto.chunk) - - -def convert_proto_to_bosdyn_msgs_download_edge_snapshot_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotRequest", ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.edge_snapshot_id = proto.edge_snapshot_id - - -def convert_bosdyn_msgs_download_edge_snapshot_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.edge_snapshot_id = ros_msg.edge_snapshot_id - - -def convert_proto_to_bosdyn_msgs_download_edge_snapshot_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotResponse.Status", ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_download_edge_snapshot_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_download_edge_snapshot_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotResponse", ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.edge_snapshot_id = proto.edge_snapshot_id - convert_proto_to_bosdyn_msgs_data_chunk(proto.chunk, ros_msg.chunk) - ros_msg.chunk_is_set = proto.HasField("chunk") - - -def convert_bosdyn_msgs_download_edge_snapshot_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DownloadEdgeSnapshotResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.DownloadEdgeSnapshotResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.edge_snapshot_id = ros_msg.edge_snapshot_id - if ros_msg.chunk_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.chunk, proto.chunk) - - -def convert_proto_to_bosdyn_msgs_area_callback_service_error(proto: "bosdyn.api.graph_nav.graph_nav_pb2.AreaCallbackServiceError", ros_msg: "bosdyn_msgs.msgs.AreaCallbackServiceError") -> None: - ros_msg.missing_services = [] - for _item in proto.missing_services: - ros_msg.missing_services.append(_item) - from bosdyn_msgs.msg import ServiceFault - ros_msg.faulted_services = [] - for _item in proto.faulted_services: - ros_msg.faulted_services.append(ServiceFault()) - convert_proto_to_bosdyn_msgs_service_fault(_item, ros_msg.faulted_services[-1]) - - -def convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackServiceError", proto: "bosdyn.api.graph_nav.graph_nav_pb2.AreaCallbackServiceError") -> None: - proto.Clear() - del proto.missing_services[:] - for _item in ros_msg.missing_services: - proto.missing_services.append(_item) - del proto.faulted_services[:] - for _item in ros_msg.faulted_services: - convert_bosdyn_msgs_service_fault_to_proto(_item, proto.faulted_services.add()) - - -def convert_proto_to_bosdyn_msgs_validate_graph_request(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphRequest", ros_msg: "bosdyn_msgs.msgs.ValidateGraphRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_validate_graph_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ValidateGraphRequest", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_validate_graph_response_status(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphResponse.Status", ros_msg: "bosdyn_msgs.msgs.ValidateGraphResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_validate_graph_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ValidateGraphResponseStatus", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_validate_graph_response(proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphResponse", ros_msg: "bosdyn_msgs.msgs.ValidateGraphResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_sensor_compatibility_status(proto.sensor_status, ros_msg.sensor_status) - ros_msg.sensor_status_is_set = proto.HasField("sensor_status") - convert_proto_to_bosdyn_msgs_area_callback_service_error(proto.area_callback_error, ros_msg.area_callback_error) - ros_msg.area_callback_error_is_set = proto.HasField("area_callback_error") - - -def convert_bosdyn_msgs_validate_graph_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ValidateGraphResponse", proto: "bosdyn.api.graph_nav.graph_nav_pb2.ValidateGraphResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.sensor_status_is_set: - convert_bosdyn_msgs_sensor_compatibility_status_to_proto(ros_msg.sensor_status, proto.sensor_status) - if ros_msg.area_callback_error_is_set: - convert_bosdyn_msgs_area_callback_service_error_to_proto(ros_msg.area_callback_error, proto.area_callback_error) - - -def convert_proto_to_bosdyn_msgs_annotation_state(proto: "bosdyn.api.graph_nav.map_pb2.AnnotationState", ros_msg: "bosdyn_msgs.msgs.AnnotationState") -> None: - pass - - -def convert_bosdyn_msgs_annotation_state_to_proto(ros_msg: "bosdyn_msgs.msgs.AnnotationState", proto: "bosdyn.api.graph_nav.map_pb2.AnnotationState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_waypoint_waypoint_source(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.WaypointSource", ros_msg: "bosdyn_msgs.msgs.WaypointWaypointSource") -> None: - pass - - -def convert_bosdyn_msgs_waypoint_waypoint_source_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointWaypointSource", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.WaypointSource") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_default(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Default", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionDefault") -> None: - pass - - -def convert_bosdyn_msgs_waypoint_annotations_localize_region_default_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionDefault", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Default") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_empty(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Empty", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionEmpty") -> None: - pass - - -def convert_bosdyn_msgs_waypoint_annotations_localize_region_empty_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionEmpty", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Empty") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_circle2_d(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Circle2D", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionCircle2D") -> None: - ros_msg.dist_2d = proto.dist_2d - - -def convert_bosdyn_msgs_waypoint_annotations_localize_region_circle2_d_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionCircle2D", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion.Circle2D") -> None: - proto.Clear() - proto.dist_2d = ros_msg.dist_2d - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_one_of_region(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionOneOfRegion") -> None: - if proto.HasField("default_region"): - ros_msg.region_choice = ros_msg.REGION_DEFAULT_REGION_SET - convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_default(proto.default_region, ros_msg.default_region) - if proto.HasField("empty"): - ros_msg.region_choice = ros_msg.REGION_EMPTY_SET - convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_empty(proto.empty, ros_msg.empty) - if proto.HasField("circle"): - ros_msg.region_choice = ros_msg.REGION_CIRCLE_SET - convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_circle2_d(proto.circle, ros_msg.circle) - - -def convert_bosdyn_msgs_waypoint_annotations_localize_region_one_of_region_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegionOneOfRegion", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion") -> None: - proto.ClearField("region") - if ros_msg.region_choice == ros_msg.REGION_DEFAULT_REGION_SET: - convert_bosdyn_msgs_waypoint_annotations_localize_region_default_to_proto(ros_msg.default_region, proto.default_region) - if ros_msg.region_choice == ros_msg.REGION_EMPTY_SET: - convert_bosdyn_msgs_waypoint_annotations_localize_region_empty_to_proto(ros_msg.empty, proto.empty) - if ros_msg.region_choice == ros_msg.REGION_CIRCLE_SET: - convert_bosdyn_msgs_waypoint_annotations_localize_region_circle2_d_to_proto(ros_msg.circle, proto.circle) - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegion") -> None: - ros_msg.state.value = proto.state - convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region_one_of_region(proto, ros_msg.region) - - -def convert_bosdyn_msgs_waypoint_annotations_localize_region_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLocalizeRegion", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LocalizeRegion") -> None: - proto.Clear() - proto.state = ros_msg.state.value - convert_bosdyn_msgs_waypoint_annotations_localize_region_one_of_region_to_proto(ros_msg.region, proto) - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations_loop_closure_settings(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LoopClosureSettings", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLoopClosureSettings") -> None: - ros_msg.disable_loop_closure = proto.disable_loop_closure - ros_msg.disable_collision_check = proto.disable_collision_check - ros_msg.max_edge_length = proto.max_edge_length - ros_msg.max_odometry_path_length = proto.max_odometry_path_length - - -def convert_bosdyn_msgs_waypoint_annotations_loop_closure_settings_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotationsLoopClosureSettings", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations.LoopClosureSettings") -> None: - proto.Clear() - proto.disable_loop_closure = ros_msg.disable_loop_closure - proto.disable_collision_check = ros_msg.disable_collision_check - proto.max_edge_length = ros_msg.max_edge_length - proto.max_odometry_path_length = ros_msg.max_odometry_path_length - - -def convert_proto_to_bosdyn_msgs_waypoint_annotations(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations", ros_msg: "bosdyn_msgs.msgs.WaypointAnnotations") -> None: - ros_msg.name = proto.name - convert_proto_to_builtin_interfaces_time(proto.creation_time, ros_msg.creation_time) - ros_msg.creation_time_is_set = proto.HasField("creation_time") - convert_proto_to_bosdyn_msgs_se3_covariance(proto.icp_variance, ros_msg.icp_variance) - ros_msg.icp_variance_is_set = proto.HasField("icp_variance") - convert_proto_to_bosdyn_msgs_waypoint_annotations_localize_region(proto.scan_match_region, ros_msg.scan_match_region) - ros_msg.scan_match_region_is_set = proto.HasField("scan_match_region") - ros_msg.waypoint_source.value = proto.waypoint_source - convert_proto_to_bosdyn_msgs_client_metadata(proto.client_metadata, ros_msg.client_metadata) - ros_msg.client_metadata_is_set = proto.HasField("client_metadata") - convert_proto_to_bosdyn_msgs_waypoint_annotations_loop_closure_settings(proto.loop_closure_settings, ros_msg.loop_closure_settings) - ros_msg.loop_closure_settings_is_set = proto.HasField("loop_closure_settings") - - -def convert_bosdyn_msgs_waypoint_annotations_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnnotations", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint.Annotations") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.creation_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.creation_time, proto.creation_time) - if ros_msg.icp_variance_is_set: - convert_bosdyn_msgs_se3_covariance_to_proto(ros_msg.icp_variance, proto.icp_variance) - if ros_msg.scan_match_region_is_set: - convert_bosdyn_msgs_waypoint_annotations_localize_region_to_proto(ros_msg.scan_match_region, proto.scan_match_region) - proto.waypoint_source = ros_msg.waypoint_source.value - if ros_msg.client_metadata_is_set: - convert_bosdyn_msgs_client_metadata_to_proto(ros_msg.client_metadata, proto.client_metadata) - if ros_msg.loop_closure_settings_is_set: - convert_bosdyn_msgs_waypoint_annotations_loop_closure_settings_to_proto(ros_msg.loop_closure_settings, proto.loop_closure_settings) - - -def convert_proto_to_bosdyn_msgs_waypoint(proto: "bosdyn.api.graph_nav.map_pb2.Waypoint", ros_msg: "bosdyn_msgs.msgs.Waypoint") -> None: - ros_msg.id = proto.id - ros_msg.snapshot_id = proto.snapshot_id - convert_proto_to_geometry_msgs_pose(proto.waypoint_tform_ko, ros_msg.waypoint_tform_ko) - ros_msg.waypoint_tform_ko_is_set = proto.HasField("waypoint_tform_ko") - convert_proto_to_bosdyn_msgs_waypoint_annotations(proto.annotations, ros_msg.annotations) - ros_msg.annotations_is_set = proto.HasField("annotations") - - -def convert_bosdyn_msgs_waypoint_to_proto(ros_msg: "bosdyn_msgs.msgs.Waypoint", proto: "bosdyn.api.graph_nav.map_pb2.Waypoint") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.snapshot_id = ros_msg.snapshot_id - if ros_msg.waypoint_tform_ko_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.waypoint_tform_ko, proto.waypoint_tform_ko) - if ros_msg.annotations_is_set: - convert_bosdyn_msgs_waypoint_annotations_to_proto(ros_msg.annotations, proto.annotations) - - -def convert_proto_to_bosdyn_msgs_client_metadata(proto: "bosdyn.api.graph_nav.map_pb2.ClientMetadata", ros_msg: "bosdyn_msgs.msgs.ClientMetadata") -> None: - ros_msg.session_name = proto.session_name - ros_msg.client_username = proto.client_username - ros_msg.client_software_version = proto.client_software_version - ros_msg.client_id = proto.client_id - ros_msg.client_type = proto.client_type - - -def convert_bosdyn_msgs_client_metadata_to_proto(ros_msg: "bosdyn_msgs.msgs.ClientMetadata", proto: "bosdyn.api.graph_nav.map_pb2.ClientMetadata") -> None: - proto.Clear() - proto.session_name = ros_msg.session_name - proto.client_username = ros_msg.client_username - proto.client_software_version = ros_msg.client_software_version - proto.client_id = ros_msg.client_id - proto.client_type = ros_msg.client_type - - -def convert_proto_to_bosdyn_msgs_waypoint_snapshot(proto: "bosdyn.api.graph_nav.map_pb2.WaypointSnapshot", ros_msg: "bosdyn_msgs.msgs.WaypointSnapshot") -> None: - ros_msg.id = proto.id - from bosdyn_msgs.msg import ImageResponse - ros_msg.images = [] - for _item in proto.images: - ros_msg.images.append(ImageResponse()) - convert_proto_to_bosdyn_msgs_image_response(_item, ros_msg.images[-1]) - convert_proto_to_bosdyn_msgs_point_cloud(proto.point_cloud, ros_msg.point_cloud) - ros_msg.point_cloud_is_set = proto.HasField("point_cloud") - from bosdyn_msgs.msg import WorldObject - ros_msg.objects = [] - for _item in proto.objects: - ros_msg.objects.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.objects[-1]) - convert_proto_to_bosdyn_msgs_robot_state(proto.robot_state, ros_msg.robot_state) - ros_msg.robot_state_is_set = proto.HasField("robot_state") - from bosdyn_msgs.msg import LocalGrid - ros_msg.robot_local_grids = [] - for _item in proto.robot_local_grids: - ros_msg.robot_local_grids.append(LocalGrid()) - convert_proto_to_bosdyn_msgs_local_grid(_item, ros_msg.robot_local_grids[-1]) - ros_msg.is_point_cloud_processed = proto.is_point_cloud_processed - ros_msg.version_id = proto.version_id - ros_msg.has_remote_point_cloud_sensor = proto.has_remote_point_cloud_sensor - convert_proto_to_geometry_msgs_pose(proto.body_tform_remote_point_cloud_sensor, ros_msg.body_tform_remote_point_cloud_sensor) - ros_msg.body_tform_remote_point_cloud_sensor_is_set = proto.HasField("body_tform_remote_point_cloud_sensor") - from bosdyn_msgs.msg import Payload - ros_msg.payloads = [] - for _item in proto.payloads: - ros_msg.payloads.append(Payload()) - convert_proto_to_bosdyn_msgs_payload(_item, ros_msg.payloads[-1]) - convert_proto_to_bosdyn_msgs_robot_id(proto.robot_id, ros_msg.robot_id) - ros_msg.robot_id_is_set = proto.HasField("robot_id") - convert_proto_to_builtin_interfaces_time(proto.recording_started_on, ros_msg.recording_started_on) - ros_msg.recording_started_on_is_set = proto.HasField("recording_started_on") - - -def convert_bosdyn_msgs_waypoint_snapshot_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointSnapshot", proto: "bosdyn.api.graph_nav.map_pb2.WaypointSnapshot") -> None: - proto.Clear() - proto.id = ros_msg.id - del proto.images[:] - for _item in ros_msg.images: - convert_bosdyn_msgs_image_response_to_proto(_item, proto.images.add()) - if ros_msg.point_cloud_is_set: - convert_bosdyn_msgs_point_cloud_to_proto(ros_msg.point_cloud, proto.point_cloud) - del proto.objects[:] - for _item in ros_msg.objects: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.objects.add()) - if ros_msg.robot_state_is_set: - convert_bosdyn_msgs_robot_state_to_proto(ros_msg.robot_state, proto.robot_state) - del proto.robot_local_grids[:] - for _item in ros_msg.robot_local_grids: - convert_bosdyn_msgs_local_grid_to_proto(_item, proto.robot_local_grids.add()) - proto.is_point_cloud_processed = ros_msg.is_point_cloud_processed - proto.version_id = ros_msg.version_id - proto.has_remote_point_cloud_sensor = ros_msg.has_remote_point_cloud_sensor - if ros_msg.body_tform_remote_point_cloud_sensor_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.body_tform_remote_point_cloud_sensor, proto.body_tform_remote_point_cloud_sensor) - del proto.payloads[:] - for _item in ros_msg.payloads: - convert_bosdyn_msgs_payload_to_proto(_item, proto.payloads.add()) - if ros_msg.robot_id_is_set: - convert_bosdyn_msgs_robot_id_to_proto(ros_msg.robot_id, proto.robot_id) - if ros_msg.recording_started_on_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.recording_started_on, proto.recording_started_on) - - -def convert_proto_to_bosdyn_msgs_edge_id(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Id", ros_msg: "bosdyn_msgs.msgs.EdgeId") -> None: - ros_msg.from_waypoint = proto.from_waypoint - ros_msg.to_waypoint = proto.to_waypoint - - -def convert_bosdyn_msgs_edge_id_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeId", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Id") -> None: - proto.Clear() - proto.from_waypoint = ros_msg.from_waypoint - proto.to_waypoint = ros_msg.to_waypoint - - -def convert_proto_to_bosdyn_msgs_edge_edge_source(proto: "bosdyn.api.graph_nav.map_pb2.Edge.EdgeSource", ros_msg: "bosdyn_msgs.msgs.EdgeEdgeSource") -> None: - pass - - -def convert_bosdyn_msgs_edge_edge_source_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeEdgeSource", proto: "bosdyn.api.graph_nav.map_pb2.Edge.EdgeSource") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_edge_annotations_stair_data(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.StairData", ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsStairData") -> None: - ros_msg.state.value = proto.state - convert_proto_to_bosdyn_msgs_staircase_with_landings(proto.staircase_with_landings, ros_msg.staircase_with_landings) - ros_msg.staircase_with_landings_is_set = proto.HasField("staircase_with_landings") - - -def convert_bosdyn_msgs_edge_annotations_stair_data_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsStairData", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.StairData") -> None: - proto.Clear() - proto.state = ros_msg.state.value - if ros_msg.staircase_with_landings_is_set: - convert_bosdyn_msgs_staircase_with_landings_to_proto(ros_msg.staircase_with_landings, proto.staircase_with_landings) - - -def convert_proto_to_bosdyn_msgs_edge_annotations_direction_constraint(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.DirectionConstraint", ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsDirectionConstraint") -> None: - pass - - -def convert_bosdyn_msgs_edge_annotations_direction_constraint_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsDirectionConstraint", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.DirectionConstraint") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_edge_annotations_path_following_mode(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.PathFollowingMode", ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsPathFollowingMode") -> None: - pass - - -def convert_bosdyn_msgs_edge_annotations_path_following_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsPathFollowingMode", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.PathFollowingMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_edge_annotations_ground_clutter_avoidance_mode(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.GroundClutterAvoidanceMode", ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsGroundClutterAvoidanceMode") -> None: - pass - - -def convert_bosdyn_msgs_edge_annotations_ground_clutter_avoidance_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeAnnotationsGroundClutterAvoidanceMode", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations.GroundClutterAvoidanceMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_edge_annotations(proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations", ros_msg: "bosdyn_msgs.msgs.EdgeAnnotations") -> None: - convert_proto_to_bosdyn_msgs_edge_annotations_stair_data(proto.stairs, ros_msg.stairs) - ros_msg.stairs_is_set = proto.HasField("stairs") - ros_msg.direction_constraint.value = proto.direction_constraint - ros_msg.require_alignment = proto.require_alignment.value - ros_msg.require_alignment_is_set = proto.HasField("require_alignment") - convert_proto_to_bosdyn_msgs_mobility_params(proto.mobility_params, ros_msg.mobility_params) - ros_msg.mobility_params_is_set = proto.HasField("mobility_params") - ros_msg.cost = proto.cost.value - ros_msg.cost_is_set = proto.HasField("cost") - ros_msg.edge_source.value = proto.edge_source - ros_msg.disable_alternate_route_finding = proto.disable_alternate_route_finding - ros_msg.path_following_mode.value = proto.path_following_mode - ros_msg.disable_directed_exploration = proto.disable_directed_exploration - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsAreaCallbackRegion - ros_msg.area_callbacks = [] - for _item in proto.area_callbacks: - ros_msg.area_callbacks.append(KeyStringValueBosdynMsgsAreaCallbackRegion()) - ros_msg.area_callbacks[-1].key = _item - convert_proto_to_bosdyn_msgs_area_callback_region(proto.area_callbacks[_item], ros_msg.area_callbacks[-1].value) - ros_msg.ground_clutter_mode.value = proto.ground_clutter_mode - - -def convert_bosdyn_msgs_edge_annotations_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeAnnotations", proto: "bosdyn.api.graph_nav.map_pb2.Edge.Annotations") -> None: - proto.Clear() - if ros_msg.stairs_is_set: - convert_bosdyn_msgs_edge_annotations_stair_data_to_proto(ros_msg.stairs, proto.stairs) - proto.direction_constraint = ros_msg.direction_constraint.value - if ros_msg.require_alignment_is_set: - convert_bool_to_proto(ros_msg.require_alignment, proto.require_alignment) - if ros_msg.mobility_params_is_set: - convert_bosdyn_msgs_mobility_params_to_proto(ros_msg.mobility_params, proto.mobility_params) - if ros_msg.cost_is_set: - convert_float64_to_proto(ros_msg.cost, proto.cost) - proto.edge_source = ros_msg.edge_source.value - proto.disable_alternate_route_finding = ros_msg.disable_alternate_route_finding - proto.path_following_mode = ros_msg.path_following_mode.value - proto.disable_directed_exploration = ros_msg.disable_directed_exploration - for _item in ros_msg.area_callbacks: - convert_bosdyn_msgs_area_callback_region_to_proto(_item.value, proto.area_callbacks[_item.key]) - proto.ground_clutter_mode = ros_msg.ground_clutter_mode.value - - -def convert_proto_to_bosdyn_msgs_edge(proto: "bosdyn.api.graph_nav.map_pb2.Edge", ros_msg: "bosdyn_msgs.msgs.Edge") -> None: - convert_proto_to_bosdyn_msgs_edge_id(proto.id, ros_msg.id) - ros_msg.id_is_set = proto.HasField("id") - ros_msg.snapshot_id = proto.snapshot_id - convert_proto_to_geometry_msgs_pose(proto.from_tform_to, ros_msg.from_tform_to) - ros_msg.from_tform_to_is_set = proto.HasField("from_tform_to") - convert_proto_to_bosdyn_msgs_edge_annotations(proto.annotations, ros_msg.annotations) - ros_msg.annotations_is_set = proto.HasField("annotations") - - -def convert_bosdyn_msgs_edge_to_proto(ros_msg: "bosdyn_msgs.msgs.Edge", proto: "bosdyn.api.graph_nav.map_pb2.Edge") -> None: - proto.Clear() - if ros_msg.id_is_set: - convert_bosdyn_msgs_edge_id_to_proto(ros_msg.id, proto.id) - proto.snapshot_id = ros_msg.snapshot_id - if ros_msg.from_tform_to_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.from_tform_to, proto.from_tform_to) - if ros_msg.annotations_is_set: - convert_bosdyn_msgs_edge_annotations_to_proto(ros_msg.annotations, proto.annotations) - - -def convert_proto_to_bosdyn_msgs_edge_snapshot_stance(proto: "bosdyn.api.graph_nav.map_pb2.EdgeSnapshot.Stance", ros_msg: "bosdyn_msgs.msgs.EdgeSnapshotStance") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - from bosdyn_msgs.msg import FootState - ros_msg.foot_states = [] - for _item in proto.foot_states: - ros_msg.foot_states.append(FootState()) - convert_proto_to_bosdyn_msgs_foot_state(_item, ros_msg.foot_states[-1]) - convert_proto_to_geometry_msgs_pose(proto.ko_tform_body, ros_msg.ko_tform_body) - ros_msg.ko_tform_body_is_set = proto.HasField("ko_tform_body") - convert_proto_to_geometry_msgs_pose(proto.vision_tform_body, ros_msg.vision_tform_body) - ros_msg.vision_tform_body_is_set = proto.HasField("vision_tform_body") - ros_msg.planar_ground = proto.planar_ground.value - ros_msg.planar_ground_is_set = proto.HasField("planar_ground") - - -def convert_bosdyn_msgs_edge_snapshot_stance_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeSnapshotStance", proto: "bosdyn.api.graph_nav.map_pb2.EdgeSnapshot.Stance") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - del proto.foot_states[:] - for _item in ros_msg.foot_states: - convert_bosdyn_msgs_foot_state_to_proto(_item, proto.foot_states.add()) - if ros_msg.ko_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.ko_tform_body, proto.ko_tform_body) - if ros_msg.vision_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.vision_tform_body, proto.vision_tform_body) - if ros_msg.planar_ground_is_set: - convert_bool_to_proto(ros_msg.planar_ground, proto.planar_ground) - - -def convert_proto_to_bosdyn_msgs_edge_snapshot(proto: "bosdyn.api.graph_nav.map_pb2.EdgeSnapshot", ros_msg: "bosdyn_msgs.msgs.EdgeSnapshot") -> None: - ros_msg.id = proto.id - from bosdyn_msgs.msg import EdgeSnapshotStance - ros_msg.stances = [] - for _item in proto.stances: - ros_msg.stances.append(EdgeSnapshotStance()) - convert_proto_to_bosdyn_msgs_edge_snapshot_stance(_item, ros_msg.stances[-1]) - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsAreaCallbackData - ros_msg.area_callbacks = [] - for _item in proto.area_callbacks: - ros_msg.area_callbacks.append(KeyStringValueBosdynMsgsAreaCallbackData()) - ros_msg.area_callbacks[-1].key = _item - convert_proto_to_bosdyn_msgs_area_callback_data(proto.area_callbacks[_item], ros_msg.area_callbacks[-1].value) - - -def convert_bosdyn_msgs_edge_snapshot_to_proto(ros_msg: "bosdyn_msgs.msgs.EdgeSnapshot", proto: "bosdyn.api.graph_nav.map_pb2.EdgeSnapshot") -> None: - proto.Clear() - proto.id = ros_msg.id - del proto.stances[:] - for _item in ros_msg.stances: - convert_bosdyn_msgs_edge_snapshot_stance_to_proto(_item, proto.stances.add()) - for _item in ros_msg.area_callbacks: - convert_bosdyn_msgs_area_callback_data_to_proto(_item.value, proto.area_callbacks[_item.key]) - - -def convert_proto_to_bosdyn_msgs_anchor(proto: "bosdyn.api.graph_nav.map_pb2.Anchor", ros_msg: "bosdyn_msgs.msgs.Anchor") -> None: - ros_msg.id = proto.id - convert_proto_to_geometry_msgs_pose(proto.seed_tform_waypoint, ros_msg.seed_tform_waypoint) - ros_msg.seed_tform_waypoint_is_set = proto.HasField("seed_tform_waypoint") - - -def convert_bosdyn_msgs_anchor_to_proto(ros_msg: "bosdyn_msgs.msgs.Anchor", proto: "bosdyn.api.graph_nav.map_pb2.Anchor") -> None: - proto.Clear() - proto.id = ros_msg.id - if ros_msg.seed_tform_waypoint_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.seed_tform_waypoint, proto.seed_tform_waypoint) - - -def convert_proto_to_bosdyn_msgs_anchored_world_object(proto: "bosdyn.api.graph_nav.map_pb2.AnchoredWorldObject", ros_msg: "bosdyn_msgs.msgs.AnchoredWorldObject") -> None: - ros_msg.id = proto.id - convert_proto_to_geometry_msgs_pose(proto.seed_tform_object, ros_msg.seed_tform_object) - ros_msg.seed_tform_object_is_set = proto.HasField("seed_tform_object") - - -def convert_bosdyn_msgs_anchored_world_object_to_proto(ros_msg: "bosdyn_msgs.msgs.AnchoredWorldObject", proto: "bosdyn.api.graph_nav.map_pb2.AnchoredWorldObject") -> None: - proto.Clear() - proto.id = ros_msg.id - if ros_msg.seed_tform_object_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.seed_tform_object, proto.seed_tform_object) - - -def convert_proto_to_bosdyn_msgs_anchoring(proto: "bosdyn.api.graph_nav.map_pb2.Anchoring", ros_msg: "bosdyn_msgs.msgs.Anchoring") -> None: - from bosdyn_msgs.msg import Anchor - ros_msg.anchors = [] - for _item in proto.anchors: - ros_msg.anchors.append(Anchor()) - convert_proto_to_bosdyn_msgs_anchor(_item, ros_msg.anchors[-1]) - from bosdyn_msgs.msg import AnchoredWorldObject - ros_msg.objects = [] - for _item in proto.objects: - ros_msg.objects.append(AnchoredWorldObject()) - convert_proto_to_bosdyn_msgs_anchored_world_object(_item, ros_msg.objects[-1]) - - -def convert_bosdyn_msgs_anchoring_to_proto(ros_msg: "bosdyn_msgs.msgs.Anchoring", proto: "bosdyn.api.graph_nav.map_pb2.Anchoring") -> None: - proto.Clear() - del proto.anchors[:] - for _item in ros_msg.anchors: - convert_bosdyn_msgs_anchor_to_proto(_item, proto.anchors.add()) - del proto.objects[:] - for _item in ros_msg.objects: - convert_bosdyn_msgs_anchored_world_object_to_proto(_item, proto.objects.add()) - - -def convert_proto_to_bosdyn_msgs_area_callback_region(proto: "bosdyn.api.graph_nav.map_pb2.AreaCallbackRegion", ros_msg: "bosdyn_msgs.msgs.AreaCallbackRegion") -> None: - ros_msg.service_name = proto.service_name - ros_msg.description = proto.description - convert_proto_to_bosdyn_msgs_area_callback_data(proto.recorded_data, ros_msg.recorded_data) - ros_msg.recorded_data_is_set = proto.HasField("recorded_data") - - -def convert_bosdyn_msgs_area_callback_region_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackRegion", proto: "bosdyn.api.graph_nav.map_pb2.AreaCallbackRegion") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.description = ros_msg.description - if ros_msg.recorded_data_is_set: - convert_bosdyn_msgs_area_callback_data_to_proto(ros_msg.recorded_data, proto.recorded_data) - - -def convert_proto_to_bosdyn_msgs_graph(proto: "bosdyn.api.graph_nav.map_pb2.Graph", ros_msg: "bosdyn_msgs.msgs.Graph") -> None: - from bosdyn_msgs.msg import Waypoint - ros_msg.waypoints = [] - for _item in proto.waypoints: - ros_msg.waypoints.append(Waypoint()) - convert_proto_to_bosdyn_msgs_waypoint(_item, ros_msg.waypoints[-1]) - from bosdyn_msgs.msg import Edge - ros_msg.edges = [] - for _item in proto.edges: - ros_msg.edges.append(Edge()) - convert_proto_to_bosdyn_msgs_edge(_item, ros_msg.edges[-1]) - convert_proto_to_bosdyn_msgs_anchoring(proto.anchoring, ros_msg.anchoring) - ros_msg.anchoring_is_set = proto.HasField("anchoring") - - -def convert_bosdyn_msgs_graph_to_proto(ros_msg: "bosdyn_msgs.msgs.Graph", proto: "bosdyn.api.graph_nav.map_pb2.Graph") -> None: - proto.Clear() - del proto.waypoints[:] - for _item in ros_msg.waypoints: - convert_bosdyn_msgs_waypoint_to_proto(_item, proto.waypoints.add()) - del proto.edges[:] - for _item in ros_msg.edges: - convert_bosdyn_msgs_edge_to_proto(_item, proto.edges.add()) - if ros_msg.anchoring_is_set: - convert_bosdyn_msgs_anchoring_to_proto(ros_msg.anchoring, proto.anchoring) - - -def convert_proto_to_bosdyn_msgs_map_stats_stat(proto: "bosdyn.api.graph_nav.map_pb2.MapStats.Stat", ros_msg: "bosdyn_msgs.msgs.MapStatsStat") -> None: - ros_msg.count = proto.count - ros_msg.num_bytes = proto.num_bytes - - -def convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg: "bosdyn_msgs.msgs.MapStatsStat", proto: "bosdyn.api.graph_nav.map_pb2.MapStats.Stat") -> None: - proto.Clear() - proto.count = ros_msg.count - proto.num_bytes = ros_msg.num_bytes - - -def convert_proto_to_bosdyn_msgs_map_stats(proto: "bosdyn.api.graph_nav.map_pb2.MapStats", ros_msg: "bosdyn_msgs.msgs.MapStats") -> None: - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.waypoints, ros_msg.waypoints) - ros_msg.waypoints_is_set = proto.HasField("waypoints") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.waypoint_snapshots, ros_msg.waypoint_snapshots) - ros_msg.waypoint_snapshots_is_set = proto.HasField("waypoint_snapshots") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.alternate_waypoints, ros_msg.alternate_waypoints) - ros_msg.alternate_waypoints_is_set = proto.HasField("alternate_waypoints") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.edges, ros_msg.edges) - ros_msg.edges_is_set = proto.HasField("edges") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.edge_snapshots, ros_msg.edge_snapshots) - ros_msg.edge_snapshots_is_set = proto.HasField("edge_snapshots") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.alternate_edges, ros_msg.alternate_edges) - ros_msg.alternate_edges_is_set = proto.HasField("alternate_edges") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.waypoint_anchors, ros_msg.waypoint_anchors) - ros_msg.waypoint_anchors_is_set = proto.HasField("waypoint_anchors") - convert_proto_to_bosdyn_msgs_map_stats_stat(proto.object_anchors, ros_msg.object_anchors) - ros_msg.object_anchors_is_set = proto.HasField("object_anchors") - ros_msg.total_path_length = proto.total_path_length - - -def convert_bosdyn_msgs_map_stats_to_proto(ros_msg: "bosdyn_msgs.msgs.MapStats", proto: "bosdyn.api.graph_nav.map_pb2.MapStats") -> None: - proto.Clear() - if ros_msg.waypoints_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.waypoints, proto.waypoints) - if ros_msg.waypoint_snapshots_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.waypoint_snapshots, proto.waypoint_snapshots) - if ros_msg.alternate_waypoints_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.alternate_waypoints, proto.alternate_waypoints) - if ros_msg.edges_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.edges, proto.edges) - if ros_msg.edge_snapshots_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.edge_snapshots, proto.edge_snapshots) - if ros_msg.alternate_edges_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.alternate_edges, proto.alternate_edges) - if ros_msg.waypoint_anchors_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.waypoint_anchors, proto.waypoint_anchors) - if ros_msg.object_anchors_is_set: - convert_bosdyn_msgs_map_stats_stat_to_proto(ros_msg.object_anchors, proto.object_anchors) - proto.total_path_length = ros_msg.total_path_length - - -def convert_proto_to_bosdyn_msgs_process_topology_request_icp_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.ICPParams", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestICPParams") -> None: - ros_msg.icp_iters = proto.icp_iters.value - ros_msg.icp_iters_is_set = proto.HasField("icp_iters") - ros_msg.max_point_match_distance = proto.max_point_match_distance.value - ros_msg.max_point_match_distance_is_set = proto.HasField("max_point_match_distance") - - -def convert_bosdyn_msgs_process_topology_request_icp_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestICPParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.ICPParams") -> None: - proto.Clear() - if ros_msg.icp_iters_is_set: - convert_int32_to_proto(ros_msg.icp_iters, proto.icp_iters) - if ros_msg.max_point_match_distance_is_set: - convert_float64_to_proto(ros_msg.max_point_match_distance, proto.max_point_match_distance) - - -def convert_proto_to_bosdyn_msgs_process_topology_request_odometry_loop_closure_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.OdometryLoopClosureParams", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestOdometryLoopClosureParams") -> None: - ros_msg.max_loop_closure_path_length = proto.max_loop_closure_path_length.value - ros_msg.max_loop_closure_path_length_is_set = proto.HasField("max_loop_closure_path_length") - ros_msg.min_loop_closure_path_length = proto.min_loop_closure_path_length.value - ros_msg.min_loop_closure_path_length_is_set = proto.HasField("min_loop_closure_path_length") - ros_msg.max_loop_closure_height_change = proto.max_loop_closure_height_change.value - ros_msg.max_loop_closure_height_change_is_set = proto.HasField("max_loop_closure_height_change") - ros_msg.max_loop_closure_edge_length = proto.max_loop_closure_edge_length.value - ros_msg.max_loop_closure_edge_length_is_set = proto.HasField("max_loop_closure_edge_length") - ros_msg.num_extra_loop_closure_iterations = proto.num_extra_loop_closure_iterations.value - ros_msg.num_extra_loop_closure_iterations_is_set = proto.HasField("num_extra_loop_closure_iterations") - ros_msg.prune_edges = proto.prune_edges.value - ros_msg.prune_edges_is_set = proto.HasField("prune_edges") - - -def convert_bosdyn_msgs_process_topology_request_odometry_loop_closure_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestOdometryLoopClosureParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.OdometryLoopClosureParams") -> None: - proto.Clear() - if ros_msg.max_loop_closure_path_length_is_set: - convert_float64_to_proto(ros_msg.max_loop_closure_path_length, proto.max_loop_closure_path_length) - if ros_msg.min_loop_closure_path_length_is_set: - convert_float64_to_proto(ros_msg.min_loop_closure_path_length, proto.min_loop_closure_path_length) - if ros_msg.max_loop_closure_height_change_is_set: - convert_float64_to_proto(ros_msg.max_loop_closure_height_change, proto.max_loop_closure_height_change) - if ros_msg.max_loop_closure_edge_length_is_set: - convert_float64_to_proto(ros_msg.max_loop_closure_edge_length, proto.max_loop_closure_edge_length) - if ros_msg.num_extra_loop_closure_iterations_is_set: - convert_int32_to_proto(ros_msg.num_extra_loop_closure_iterations, proto.num_extra_loop_closure_iterations) - if ros_msg.prune_edges_is_set: - convert_bool_to_proto(ros_msg.prune_edges, proto.prune_edges) - - -def convert_proto_to_bosdyn_msgs_process_topology_request_fiducial_loop_closure_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.FiducialLoopClosureParams", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestFiducialLoopClosureParams") -> None: - ros_msg.min_loop_closure_path_length = proto.min_loop_closure_path_length.value - ros_msg.min_loop_closure_path_length_is_set = proto.HasField("min_loop_closure_path_length") - ros_msg.max_loop_closure_edge_length = proto.max_loop_closure_edge_length.value - ros_msg.max_loop_closure_edge_length_is_set = proto.HasField("max_loop_closure_edge_length") - ros_msg.max_fiducial_distance = proto.max_fiducial_distance.value - ros_msg.max_fiducial_distance_is_set = proto.HasField("max_fiducial_distance") - ros_msg.max_loop_closure_height_change = proto.max_loop_closure_height_change.value - ros_msg.max_loop_closure_height_change_is_set = proto.HasField("max_loop_closure_height_change") - ros_msg.prune_edges = proto.prune_edges.value - ros_msg.prune_edges_is_set = proto.HasField("prune_edges") - - -def convert_bosdyn_msgs_process_topology_request_fiducial_loop_closure_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestFiducialLoopClosureParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.FiducialLoopClosureParams") -> None: - proto.Clear() - if ros_msg.min_loop_closure_path_length_is_set: - convert_float64_to_proto(ros_msg.min_loop_closure_path_length, proto.min_loop_closure_path_length) - if ros_msg.max_loop_closure_edge_length_is_set: - convert_float64_to_proto(ros_msg.max_loop_closure_edge_length, proto.max_loop_closure_edge_length) - if ros_msg.max_fiducial_distance_is_set: - convert_float64_to_proto(ros_msg.max_fiducial_distance, proto.max_fiducial_distance) - if ros_msg.max_loop_closure_height_change_is_set: - convert_float64_to_proto(ros_msg.max_loop_closure_height_change, proto.max_loop_closure_height_change) - if ros_msg.prune_edges_is_set: - convert_bool_to_proto(ros_msg.prune_edges, proto.prune_edges) - - -def convert_proto_to_bosdyn_msgs_process_topology_request_collision_checking_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.CollisionCheckingParams", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestCollisionCheckingParams") -> None: - ros_msg.check_edges_for_collision = proto.check_edges_for_collision.value - ros_msg.check_edges_for_collision_is_set = proto.HasField("check_edges_for_collision") - ros_msg.collision_check_robot_radius = proto.collision_check_robot_radius.value - ros_msg.collision_check_robot_radius_is_set = proto.HasField("collision_check_robot_radius") - ros_msg.collision_check_height_variation = proto.collision_check_height_variation.value - ros_msg.collision_check_height_variation_is_set = proto.HasField("collision_check_height_variation") - - -def convert_bosdyn_msgs_process_topology_request_collision_checking_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestCollisionCheckingParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.CollisionCheckingParams") -> None: - proto.Clear() - if ros_msg.check_edges_for_collision_is_set: - convert_bool_to_proto(ros_msg.check_edges_for_collision, proto.check_edges_for_collision) - if ros_msg.collision_check_robot_radius_is_set: - convert_float64_to_proto(ros_msg.collision_check_robot_radius, proto.collision_check_robot_radius) - if ros_msg.collision_check_height_variation_is_set: - convert_float64_to_proto(ros_msg.collision_check_height_variation, proto.collision_check_height_variation) - - -def convert_proto_to_bosdyn_msgs_process_topology_request_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.Params", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestParams") -> None: - ros_msg.do_odometry_loop_closure = proto.do_odometry_loop_closure.value - ros_msg.do_odometry_loop_closure_is_set = proto.HasField("do_odometry_loop_closure") - convert_proto_to_bosdyn_msgs_process_topology_request_odometry_loop_closure_params(proto.odometry_loop_closure_params, ros_msg.odometry_loop_closure_params) - ros_msg.odometry_loop_closure_params_is_set = proto.HasField("odometry_loop_closure_params") - convert_proto_to_bosdyn_msgs_process_topology_request_icp_params(proto.icp_params, ros_msg.icp_params) - ros_msg.icp_params_is_set = proto.HasField("icp_params") - ros_msg.do_fiducial_loop_closure = proto.do_fiducial_loop_closure.value - ros_msg.do_fiducial_loop_closure_is_set = proto.HasField("do_fiducial_loop_closure") - convert_proto_to_bosdyn_msgs_process_topology_request_fiducial_loop_closure_params(proto.fiducial_loop_closure_params, ros_msg.fiducial_loop_closure_params) - ros_msg.fiducial_loop_closure_params_is_set = proto.HasField("fiducial_loop_closure_params") - convert_proto_to_bosdyn_msgs_process_topology_request_collision_checking_params(proto.collision_check_params, ros_msg.collision_check_params) - ros_msg.collision_check_params_is_set = proto.HasField("collision_check_params") - ros_msg.timeout_seconds = proto.timeout_seconds - - -def convert_bosdyn_msgs_process_topology_request_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequestParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest.Params") -> None: - proto.Clear() - if ros_msg.do_odometry_loop_closure_is_set: - convert_bool_to_proto(ros_msg.do_odometry_loop_closure, proto.do_odometry_loop_closure) - if ros_msg.odometry_loop_closure_params_is_set: - convert_bosdyn_msgs_process_topology_request_odometry_loop_closure_params_to_proto(ros_msg.odometry_loop_closure_params, proto.odometry_loop_closure_params) - if ros_msg.icp_params_is_set: - convert_bosdyn_msgs_process_topology_request_icp_params_to_proto(ros_msg.icp_params, proto.icp_params) - if ros_msg.do_fiducial_loop_closure_is_set: - convert_bool_to_proto(ros_msg.do_fiducial_loop_closure, proto.do_fiducial_loop_closure) - if ros_msg.fiducial_loop_closure_params_is_set: - convert_bosdyn_msgs_process_topology_request_fiducial_loop_closure_params_to_proto(ros_msg.fiducial_loop_closure_params, proto.fiducial_loop_closure_params) - if ros_msg.collision_check_params_is_set: - convert_bosdyn_msgs_process_topology_request_collision_checking_params_to_proto(ros_msg.collision_check_params, proto.collision_check_params) - proto.timeout_seconds = ros_msg.timeout_seconds - - -def convert_proto_to_bosdyn_msgs_process_topology_request(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_process_topology_request_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - ros_msg.modify_map_on_server = proto.modify_map_on_server - - -def convert_bosdyn_msgs_process_topology_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyRequest", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_process_topology_request_params_to_proto(ros_msg.params, proto.params) - proto.modify_map_on_server = ros_msg.modify_map_on_server - - -def convert_proto_to_bosdyn_msgs_process_topology_response_status(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyResponse.Status", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_process_topology_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyResponseStatus", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_process_topology_response(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyResponse", ros_msg: "bosdyn_msgs.msgs.ProcessTopologyResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_graph(proto.new_subgraph, ros_msg.new_subgraph) - ros_msg.new_subgraph_is_set = proto.HasField("new_subgraph") - ros_msg.map_on_server_was_modified = proto.map_on_server_was_modified - ros_msg.missing_snapshot_ids = [] - for _item in proto.missing_snapshot_ids: - ros_msg.missing_snapshot_ids.append(_item) - ros_msg.missing_waypoint_ids = [] - for _item in proto.missing_waypoint_ids: - ros_msg.missing_waypoint_ids.append(_item) - ros_msg.timed_out = proto.timed_out - - -def convert_bosdyn_msgs_process_topology_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessTopologyResponse", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessTopologyResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.new_subgraph_is_set: - convert_bosdyn_msgs_graph_to_proto(ros_msg.new_subgraph, proto.new_subgraph) - proto.map_on_server_was_modified = ros_msg.map_on_server_was_modified - del proto.missing_snapshot_ids[:] - for _item in ros_msg.missing_snapshot_ids: - proto.missing_snapshot_ids.append(_item) - del proto.missing_waypoint_ids[:] - for _item in ros_msg.missing_waypoint_ids: - proto.missing_waypoint_ids.append(_item) - proto.timed_out = ros_msg.timed_out - - -def convert_proto_to_bosdyn_msgs_pose_bounds(proto: "bosdyn.api.graph_nav.map_processing_pb2.PoseBounds", ros_msg: "bosdyn_msgs.msgs.PoseBounds") -> None: - ros_msg.x_bounds = proto.x_bounds - ros_msg.y_bounds = proto.y_bounds - ros_msg.z_bounds = proto.z_bounds - ros_msg.yaw_bounds = proto.yaw_bounds - - -def convert_bosdyn_msgs_pose_bounds_to_proto(ros_msg: "bosdyn_msgs.msgs.PoseBounds", proto: "bosdyn.api.graph_nav.map_processing_pb2.PoseBounds") -> None: - proto.Clear() - proto.x_bounds = ros_msg.x_bounds - proto.y_bounds = ros_msg.y_bounds - proto.z_bounds = ros_msg.z_bounds - proto.yaw_bounds = ros_msg.yaw_bounds - - -def convert_proto_to_bosdyn_msgs_anchor_hint_uncertainty_one_of_uncertainty(proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchorHintUncertainty", ros_msg: "bosdyn_msgs.msgs.AnchorHintUncertaintyOneOfUncertainty") -> None: - if proto.HasField("se3_covariance"): - ros_msg.uncertainty_choice = ros_msg.UNCERTAINTY_SE3_COVARIANCE_SET - convert_proto_to_bosdyn_msgs_se3_covariance(proto.se3_covariance, ros_msg.se3_covariance) - if proto.HasField("confidence_bounds"): - ros_msg.uncertainty_choice = ros_msg.UNCERTAINTY_CONFIDENCE_BOUNDS_SET - convert_proto_to_bosdyn_msgs_pose_bounds(proto.confidence_bounds, ros_msg.confidence_bounds) - - -def convert_bosdyn_msgs_anchor_hint_uncertainty_one_of_uncertainty_to_proto(ros_msg: "bosdyn_msgs.msgs.AnchorHintUncertaintyOneOfUncertainty", proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchorHintUncertainty") -> None: - proto.ClearField("uncertainty") - if ros_msg.uncertainty_choice == ros_msg.UNCERTAINTY_SE3_COVARIANCE_SET: - convert_bosdyn_msgs_se3_covariance_to_proto(ros_msg.se3_covariance, proto.se3_covariance) - if ros_msg.uncertainty_choice == ros_msg.UNCERTAINTY_CONFIDENCE_BOUNDS_SET: - convert_bosdyn_msgs_pose_bounds_to_proto(ros_msg.confidence_bounds, proto.confidence_bounds) - - -def convert_proto_to_bosdyn_msgs_anchor_hint_uncertainty(proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchorHintUncertainty", ros_msg: "bosdyn_msgs.msgs.AnchorHintUncertainty") -> None: - convert_proto_to_bosdyn_msgs_anchor_hint_uncertainty_one_of_uncertainty(proto, ros_msg.uncertainty) - - -def convert_bosdyn_msgs_anchor_hint_uncertainty_to_proto(ros_msg: "bosdyn_msgs.msgs.AnchorHintUncertainty", proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchorHintUncertainty") -> None: - proto.Clear() - convert_bosdyn_msgs_anchor_hint_uncertainty_one_of_uncertainty_to_proto(ros_msg.uncertainty, proto) - - -def convert_proto_to_bosdyn_msgs_waypoint_anchor_hint(proto: "bosdyn.api.graph_nav.map_processing_pb2.WaypointAnchorHint", ros_msg: "bosdyn_msgs.msgs.WaypointAnchorHint") -> None: - convert_proto_to_bosdyn_msgs_anchor(proto.waypoint_anchor, ros_msg.waypoint_anchor) - ros_msg.waypoint_anchor_is_set = proto.HasField("waypoint_anchor") - convert_proto_to_bosdyn_msgs_anchor_hint_uncertainty(proto.seed_tform_waypoint_uncertainty, ros_msg.seed_tform_waypoint_uncertainty) - ros_msg.seed_tform_waypoint_uncertainty_is_set = proto.HasField("seed_tform_waypoint_uncertainty") - convert_proto_to_bosdyn_msgs_pose_bounds(proto.seed_tform_waypoint_constraint, ros_msg.seed_tform_waypoint_constraint) - ros_msg.seed_tform_waypoint_constraint_is_set = proto.HasField("seed_tform_waypoint_constraint") - - -def convert_bosdyn_msgs_waypoint_anchor_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.WaypointAnchorHint", proto: "bosdyn.api.graph_nav.map_processing_pb2.WaypointAnchorHint") -> None: - proto.Clear() - if ros_msg.waypoint_anchor_is_set: - convert_bosdyn_msgs_anchor_to_proto(ros_msg.waypoint_anchor, proto.waypoint_anchor) - if ros_msg.seed_tform_waypoint_uncertainty_is_set: - convert_bosdyn_msgs_anchor_hint_uncertainty_to_proto(ros_msg.seed_tform_waypoint_uncertainty, proto.seed_tform_waypoint_uncertainty) - if ros_msg.seed_tform_waypoint_constraint_is_set: - convert_bosdyn_msgs_pose_bounds_to_proto(ros_msg.seed_tform_waypoint_constraint, proto.seed_tform_waypoint_constraint) - - -def convert_proto_to_bosdyn_msgs_world_object_anchor_hint(proto: "bosdyn.api.graph_nav.map_processing_pb2.WorldObjectAnchorHint", ros_msg: "bosdyn_msgs.msgs.WorldObjectAnchorHint") -> None: - convert_proto_to_bosdyn_msgs_anchored_world_object(proto.object_anchor, ros_msg.object_anchor) - ros_msg.object_anchor_is_set = proto.HasField("object_anchor") - convert_proto_to_bosdyn_msgs_anchor_hint_uncertainty(proto.seed_tform_object_uncertainty, ros_msg.seed_tform_object_uncertainty) - ros_msg.seed_tform_object_uncertainty_is_set = proto.HasField("seed_tform_object_uncertainty") - convert_proto_to_bosdyn_msgs_pose_bounds(proto.seed_tform_object_constraint, ros_msg.seed_tform_object_constraint) - ros_msg.seed_tform_object_constraint_is_set = proto.HasField("seed_tform_object_constraint") - - -def convert_bosdyn_msgs_world_object_anchor_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.WorldObjectAnchorHint", proto: "bosdyn.api.graph_nav.map_processing_pb2.WorldObjectAnchorHint") -> None: - proto.Clear() - if ros_msg.object_anchor_is_set: - convert_bosdyn_msgs_anchored_world_object_to_proto(ros_msg.object_anchor, proto.object_anchor) - if ros_msg.seed_tform_object_uncertainty_is_set: - convert_bosdyn_msgs_anchor_hint_uncertainty_to_proto(ros_msg.seed_tform_object_uncertainty, proto.seed_tform_object_uncertainty) - if ros_msg.seed_tform_object_constraint_is_set: - convert_bosdyn_msgs_pose_bounds_to_proto(ros_msg.seed_tform_object_constraint, proto.seed_tform_object_constraint) - - -def convert_proto_to_bosdyn_msgs_anchoring_hint(proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchoringHint", ros_msg: "bosdyn_msgs.msgs.AnchoringHint") -> None: - from bosdyn_msgs.msg import WaypointAnchorHint - ros_msg.waypoint_anchors = [] - for _item in proto.waypoint_anchors: - ros_msg.waypoint_anchors.append(WaypointAnchorHint()) - convert_proto_to_bosdyn_msgs_waypoint_anchor_hint(_item, ros_msg.waypoint_anchors[-1]) - from bosdyn_msgs.msg import WorldObjectAnchorHint - ros_msg.world_objects = [] - for _item in proto.world_objects: - ros_msg.world_objects.append(WorldObjectAnchorHint()) - convert_proto_to_bosdyn_msgs_world_object_anchor_hint(_item, ros_msg.world_objects[-1]) - - -def convert_bosdyn_msgs_anchoring_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.AnchoringHint", proto: "bosdyn.api.graph_nav.map_processing_pb2.AnchoringHint") -> None: - proto.Clear() - del proto.waypoint_anchors[:] - for _item in ros_msg.waypoint_anchors: - convert_bosdyn_msgs_waypoint_anchor_hint_to_proto(_item, proto.waypoint_anchors.add()) - del proto.world_objects[:] - for _item in ros_msg.world_objects: - convert_bosdyn_msgs_world_object_anchor_hint_to_proto(_item, proto.world_objects.add()) - - -def convert_proto_to_bosdyn_msgs_process_anchoring_request_params_optimizer_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.OptimizerParams", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsOptimizerParams") -> None: - ros_msg.max_iters = proto.max_iters.value - ros_msg.max_iters_is_set = proto.HasField("max_iters") - ros_msg.max_time_seconds = proto.max_time_seconds.value - ros_msg.max_time_seconds_is_set = proto.HasField("max_time_seconds") - - -def convert_bosdyn_msgs_process_anchoring_request_params_optimizer_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsOptimizerParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.OptimizerParams") -> None: - proto.Clear() - if ros_msg.max_iters_is_set: - convert_int32_to_proto(ros_msg.max_iters, proto.max_iters) - if ros_msg.max_time_seconds_is_set: - convert_float64_to_proto(ros_msg.max_time_seconds, proto.max_time_seconds) - - -def convert_proto_to_bosdyn_msgs_process_anchoring_request_params_measurement_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.MeasurementParams", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsMeasurementParams") -> None: - ros_msg.use_kinematic_odometry = proto.use_kinematic_odometry.value - ros_msg.use_kinematic_odometry_is_set = proto.HasField("use_kinematic_odometry") - ros_msg.use_visual_odometry = proto.use_visual_odometry.value - ros_msg.use_visual_odometry_is_set = proto.HasField("use_visual_odometry") - ros_msg.use_gyroscope_measurements = proto.use_gyroscope_measurements.value - ros_msg.use_gyroscope_measurements_is_set = proto.HasField("use_gyroscope_measurements") - ros_msg.use_loop_closures = proto.use_loop_closures.value - ros_msg.use_loop_closures_is_set = proto.HasField("use_loop_closures") - ros_msg.use_world_objects = proto.use_world_objects.value - ros_msg.use_world_objects_is_set = proto.HasField("use_world_objects") - - -def convert_bosdyn_msgs_process_anchoring_request_params_measurement_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsMeasurementParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.MeasurementParams") -> None: - proto.Clear() - if ros_msg.use_kinematic_odometry_is_set: - convert_bool_to_proto(ros_msg.use_kinematic_odometry, proto.use_kinematic_odometry) - if ros_msg.use_visual_odometry_is_set: - convert_bool_to_proto(ros_msg.use_visual_odometry, proto.use_visual_odometry) - if ros_msg.use_gyroscope_measurements_is_set: - convert_bool_to_proto(ros_msg.use_gyroscope_measurements, proto.use_gyroscope_measurements) - if ros_msg.use_loop_closures_is_set: - convert_bool_to_proto(ros_msg.use_loop_closures, proto.use_loop_closures) - if ros_msg.use_world_objects_is_set: - convert_bool_to_proto(ros_msg.use_world_objects, proto.use_world_objects) - - -def convert_proto_to_bosdyn_msgs_process_anchoring_request_params_weights(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.Weights", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsWeights") -> None: - ros_msg.kinematic_odometry_weight = proto.kinematic_odometry_weight - ros_msg.visual_odometry_weight = proto.visual_odometry_weight - ros_msg.world_object_weight = proto.world_object_weight - ros_msg.hint_weight = proto.hint_weight - ros_msg.gyroscope_weight = proto.gyroscope_weight - ros_msg.loop_closure_weight = proto.loop_closure_weight - - -def convert_bosdyn_msgs_process_anchoring_request_params_weights_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParamsWeights", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params.Weights") -> None: - proto.Clear() - proto.kinematic_odometry_weight = ros_msg.kinematic_odometry_weight - proto.visual_odometry_weight = ros_msg.visual_odometry_weight - proto.world_object_weight = ros_msg.world_object_weight - proto.hint_weight = ros_msg.hint_weight - proto.gyroscope_weight = ros_msg.gyroscope_weight - proto.loop_closure_weight = ros_msg.loop_closure_weight - - -def convert_proto_to_bosdyn_msgs_process_anchoring_request_params(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParams") -> None: - convert_proto_to_bosdyn_msgs_process_anchoring_request_params_optimizer_params(proto.optimizer_params, ros_msg.optimizer_params) - ros_msg.optimizer_params_is_set = proto.HasField("optimizer_params") - convert_proto_to_bosdyn_msgs_process_anchoring_request_params_measurement_params(proto.measurement_params, ros_msg.measurement_params) - ros_msg.measurement_params_is_set = proto.HasField("measurement_params") - convert_proto_to_bosdyn_msgs_process_anchoring_request_params_weights(proto.weights, ros_msg.weights) - ros_msg.weights_is_set = proto.HasField("weights") - ros_msg.optimize_existing_anchoring = proto.optimize_existing_anchoring.value - ros_msg.optimize_existing_anchoring_is_set = proto.HasField("optimize_existing_anchoring") - convert_proto_to_geometry_msgs_vector3(proto.gravity_ewrt_seed, ros_msg.gravity_ewrt_seed) - ros_msg.gravity_ewrt_seed_is_set = proto.HasField("gravity_ewrt_seed") - - -def convert_bosdyn_msgs_process_anchoring_request_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequestParams", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest.Params") -> None: - proto.Clear() - if ros_msg.optimizer_params_is_set: - convert_bosdyn_msgs_process_anchoring_request_params_optimizer_params_to_proto(ros_msg.optimizer_params, proto.optimizer_params) - if ros_msg.measurement_params_is_set: - convert_bosdyn_msgs_process_anchoring_request_params_measurement_params_to_proto(ros_msg.measurement_params, proto.measurement_params) - if ros_msg.weights_is_set: - convert_bosdyn_msgs_process_anchoring_request_params_weights_to_proto(ros_msg.weights, proto.weights) - if ros_msg.optimize_existing_anchoring_is_set: - convert_bool_to_proto(ros_msg.optimize_existing_anchoring, proto.optimize_existing_anchoring) - if ros_msg.gravity_ewrt_seed_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.gravity_ewrt_seed, proto.gravity_ewrt_seed) - - -def convert_proto_to_bosdyn_msgs_process_anchoring_request(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_process_anchoring_request_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - convert_proto_to_bosdyn_msgs_anchoring_hint(proto.initial_hint, ros_msg.initial_hint) - ros_msg.initial_hint_is_set = proto.HasField("initial_hint") - ros_msg.modify_anchoring_on_server = proto.modify_anchoring_on_server - ros_msg.stream_intermediate_results = proto.stream_intermediate_results - - -def convert_bosdyn_msgs_process_anchoring_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringRequest", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_process_anchoring_request_params_to_proto(ros_msg.params, proto.params) - if ros_msg.initial_hint_is_set: - convert_bosdyn_msgs_anchoring_hint_to_proto(ros_msg.initial_hint, proto.initial_hint) - proto.modify_anchoring_on_server = ros_msg.modify_anchoring_on_server - proto.stream_intermediate_results = ros_msg.stream_intermediate_results - - -def convert_proto_to_bosdyn_msgs_process_anchoring_response_status(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringResponse.Status", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_process_anchoring_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringResponseStatus", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_process_anchoring_response(proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringResponse", ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import Anchor - ros_msg.waypoint_results = [] - for _item in proto.waypoint_results: - ros_msg.waypoint_results.append(Anchor()) - convert_proto_to_bosdyn_msgs_anchor(_item, ros_msg.waypoint_results[-1]) - from bosdyn_msgs.msg import AnchoredWorldObject - ros_msg.world_object_results = [] - for _item in proto.world_object_results: - ros_msg.world_object_results.append(AnchoredWorldObject()) - convert_proto_to_bosdyn_msgs_anchored_world_object(_item, ros_msg.world_object_results[-1]) - ros_msg.anchoring_on_server_was_modified = proto.anchoring_on_server_was_modified - ros_msg.iteration = proto.iteration - ros_msg.cost = proto.cost - ros_msg.final_iteration = proto.final_iteration - from bosdyn_msgs.msg import WaypointAnchorHint - ros_msg.violated_waypoint_constraints = [] - for _item in proto.violated_waypoint_constraints: - ros_msg.violated_waypoint_constraints.append(WaypointAnchorHint()) - convert_proto_to_bosdyn_msgs_waypoint_anchor_hint(_item, ros_msg.violated_waypoint_constraints[-1]) - from bosdyn_msgs.msg import WorldObjectAnchorHint - ros_msg.violated_object_constraints = [] - for _item in proto.violated_object_constraints: - ros_msg.violated_object_constraints.append(WorldObjectAnchorHint()) - convert_proto_to_bosdyn_msgs_world_object_anchor_hint(_item, ros_msg.violated_object_constraints[-1]) - ros_msg.missing_snapshot_ids = [] - for _item in proto.missing_snapshot_ids: - ros_msg.missing_snapshot_ids.append(_item) - ros_msg.missing_waypoint_ids = [] - for _item in proto.missing_waypoint_ids: - ros_msg.missing_waypoint_ids.append(_item) - ros_msg.invalid_hints = [] - for _item in proto.invalid_hints: - ros_msg.invalid_hints.append(_item) - from bosdyn_msgs.msg import EdgeId - ros_msg.inconsistent_edges = [] - for _item in proto.inconsistent_edges: - ros_msg.inconsistent_edges.append(EdgeId()) - convert_proto_to_bosdyn_msgs_edge_id(_item, ros_msg.inconsistent_edges[-1]) - - -def convert_bosdyn_msgs_process_anchoring_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ProcessAnchoringResponse", proto: "bosdyn.api.graph_nav.map_processing_pb2.ProcessAnchoringResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.waypoint_results[:] - for _item in ros_msg.waypoint_results: - convert_bosdyn_msgs_anchor_to_proto(_item, proto.waypoint_results.add()) - del proto.world_object_results[:] - for _item in ros_msg.world_object_results: - convert_bosdyn_msgs_anchored_world_object_to_proto(_item, proto.world_object_results.add()) - proto.anchoring_on_server_was_modified = ros_msg.anchoring_on_server_was_modified - proto.iteration = ros_msg.iteration - proto.cost = ros_msg.cost - proto.final_iteration = ros_msg.final_iteration - del proto.violated_waypoint_constraints[:] - for _item in ros_msg.violated_waypoint_constraints: - convert_bosdyn_msgs_waypoint_anchor_hint_to_proto(_item, proto.violated_waypoint_constraints.add()) - del proto.violated_object_constraints[:] - for _item in ros_msg.violated_object_constraints: - convert_bosdyn_msgs_world_object_anchor_hint_to_proto(_item, proto.violated_object_constraints.add()) - del proto.missing_snapshot_ids[:] - for _item in ros_msg.missing_snapshot_ids: - proto.missing_snapshot_ids.append(_item) - del proto.missing_waypoint_ids[:] - for _item in ros_msg.missing_waypoint_ids: - proto.missing_waypoint_ids.append(_item) - del proto.invalid_hints[:] - for _item in ros_msg.invalid_hints: - proto.invalid_hints.append(_item) - del proto.inconsistent_edges[:] - for _item in ros_msg.inconsistent_edges: - convert_bosdyn_msgs_edge_id_to_proto(_item, proto.inconsistent_edges.add()) - - -def convert_proto_to_bosdyn_msgs_route(proto: "bosdyn.api.graph_nav.nav_pb2.Route", ros_msg: "bosdyn_msgs.msgs.Route") -> None: - ros_msg.waypoint_id = [] - for _item in proto.waypoint_id: - ros_msg.waypoint_id.append(_item) - from bosdyn_msgs.msg import EdgeId - ros_msg.edge_id = [] - for _item in proto.edge_id: - ros_msg.edge_id.append(EdgeId()) - convert_proto_to_bosdyn_msgs_edge_id(_item, ros_msg.edge_id[-1]) - - -def convert_bosdyn_msgs_route_to_proto(ros_msg: "bosdyn_msgs.msgs.Route", proto: "bosdyn.api.graph_nav.nav_pb2.Route") -> None: - proto.Clear() - del proto.waypoint_id[:] - for _item in ros_msg.waypoint_id: - proto.waypoint_id.append(_item) - del proto.edge_id[:] - for _item in ros_msg.edge_id: - convert_bosdyn_msgs_edge_id_to_proto(_item, proto.edge_id.add()) - - -def convert_proto_to_bosdyn_msgs_localization(proto: "bosdyn.api.graph_nav.nav_pb2.Localization", ros_msg: "bosdyn_msgs.msgs.Localization") -> None: - ros_msg.waypoint_id = proto.waypoint_id - convert_proto_to_geometry_msgs_pose(proto.waypoint_tform_body, ros_msg.waypoint_tform_body) - ros_msg.waypoint_tform_body_is_set = proto.HasField("waypoint_tform_body") - convert_proto_to_geometry_msgs_pose(proto.seed_tform_body, ros_msg.seed_tform_body) - ros_msg.seed_tform_body_is_set = proto.HasField("seed_tform_body") - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - - -def convert_bosdyn_msgs_localization_to_proto(ros_msg: "bosdyn_msgs.msgs.Localization", proto: "bosdyn.api.graph_nav.nav_pb2.Localization") -> None: - proto.Clear() - proto.waypoint_id = ros_msg.waypoint_id - if ros_msg.waypoint_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.waypoint_tform_body, proto.waypoint_tform_body) - if ros_msg.seed_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.seed_tform_body, proto.seed_tform_body) - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - - -def convert_proto_to_bosdyn_msgs_recording_environment(proto: "bosdyn.api.graph_nav.recording_pb2.RecordingEnvironment", ros_msg: "bosdyn_msgs.msgs.RecordingEnvironment") -> None: - ros_msg.name_prefix = proto.name_prefix - convert_proto_to_bosdyn_msgs_waypoint_annotations(proto.waypoint_environment, ros_msg.waypoint_environment) - ros_msg.waypoint_environment_is_set = proto.HasField("waypoint_environment") - convert_proto_to_bosdyn_msgs_edge_annotations(proto.edge_environment, ros_msg.edge_environment) - ros_msg.edge_environment_is_set = proto.HasField("edge_environment") - - -def convert_bosdyn_msgs_recording_environment_to_proto(ros_msg: "bosdyn_msgs.msgs.RecordingEnvironment", proto: "bosdyn.api.graph_nav.recording_pb2.RecordingEnvironment") -> None: - proto.Clear() - proto.name_prefix = ros_msg.name_prefix - if ros_msg.waypoint_environment_is_set: - convert_bosdyn_msgs_waypoint_annotations_to_proto(ros_msg.waypoint_environment, proto.waypoint_environment) - if ros_msg.edge_environment_is_set: - convert_bosdyn_msgs_edge_annotations_to_proto(ros_msg.edge_environment, proto.edge_environment) - - -def convert_proto_to_bosdyn_msgs_set_recording_environment_request(proto: "bosdyn.api.graph_nav.recording_pb2.SetRecordingEnvironmentRequest", ros_msg: "bosdyn_msgs.msgs.SetRecordingEnvironmentRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_recording_environment(proto.environment, ros_msg.environment) - ros_msg.environment_is_set = proto.HasField("environment") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_set_recording_environment_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetRecordingEnvironmentRequest", proto: "bosdyn.api.graph_nav.recording_pb2.SetRecordingEnvironmentRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.environment_is_set: - convert_bosdyn_msgs_recording_environment_to_proto(ros_msg.environment, proto.environment) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_set_recording_environment_response(proto: "bosdyn.api.graph_nav.recording_pb2.SetRecordingEnvironmentResponse", ros_msg: "bosdyn_msgs.msgs.SetRecordingEnvironmentResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_set_recording_environment_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetRecordingEnvironmentResponse", proto: "bosdyn.api.graph_nav.recording_pb2.SetRecordingEnvironmentResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_start_recording_request(proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingRequest", ros_msg: "bosdyn_msgs.msgs.StartRecordingRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_recording_environment(proto.recording_environment, ros_msg.recording_environment) - ros_msg.recording_environment_is_set = proto.HasField("recording_environment") - ros_msg.require_fiducials = [] - for _item in proto.require_fiducials: - ros_msg.require_fiducials.append(_item) - convert_proto_to_builtin_interfaces_time(proto.session_start_time, ros_msg.session_start_time) - ros_msg.session_start_time_is_set = proto.HasField("session_start_time") - - -def convert_bosdyn_msgs_start_recording_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRecordingRequest", proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.recording_environment_is_set: - convert_bosdyn_msgs_recording_environment_to_proto(ros_msg.recording_environment, proto.recording_environment) - del proto.require_fiducials[:] - for _item in ros_msg.require_fiducials: - proto.require_fiducials.append(_item) - if ros_msg.session_start_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.session_start_time, proto.session_start_time) - - -def convert_proto_to_bosdyn_msgs_start_recording_response_status(proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingResponse.Status", ros_msg: "bosdyn_msgs.msgs.StartRecordingResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_start_recording_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRecordingResponseStatus", proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_start_recording_response(proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingResponse", ros_msg: "bosdyn_msgs.msgs.StartRecordingResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_waypoint(proto.created_waypoint, ros_msg.created_waypoint) - ros_msg.created_waypoint_is_set = proto.HasField("created_waypoint") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.missing_fiducials = [] - for _item in proto.missing_fiducials: - ros_msg.missing_fiducials.append(_item) - ros_msg.bad_pose_fiducials = [] - for _item in proto.bad_pose_fiducials: - ros_msg.bad_pose_fiducials.append(_item) - ros_msg.license_status.value = proto.license_status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - convert_proto_to_builtin_interfaces_time(proto.session_start_time, ros_msg.session_start_time) - ros_msg.session_start_time_is_set = proto.HasField("session_start_time") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_start_recording_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRecordingResponse", proto: "bosdyn.api.graph_nav.recording_pb2.StartRecordingResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.created_waypoint_is_set: - convert_bosdyn_msgs_waypoint_to_proto(ros_msg.created_waypoint, proto.created_waypoint) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - del proto.missing_fiducials[:] - for _item in ros_msg.missing_fiducials: - proto.missing_fiducials.append(_item) - del proto.bad_pose_fiducials[:] - for _item in ros_msg.bad_pose_fiducials: - proto.bad_pose_fiducials.append(_item) - proto.license_status = ros_msg.license_status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - if ros_msg.session_start_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.session_start_time, proto.session_start_time) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_stop_recording_request(proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingRequest", ros_msg: "bosdyn_msgs.msgs.StopRecordingRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_stop_recording_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StopRecordingRequest", proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_stop_recording_response_status(proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingResponse.Status", ros_msg: "bosdyn_msgs.msgs.StopRecordingResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_stop_recording_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StopRecordingResponseStatus", proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stop_recording_response(proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingResponse", ros_msg: "bosdyn_msgs.msgs.StopRecordingResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.error_waypoint_localized_id = proto.error_waypoint_localized_id - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - convert_proto_to_builtin_interfaces_time(proto.session_start_time, ros_msg.session_start_time) - ros_msg.session_start_time_is_set = proto.HasField("session_start_time") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_stop_recording_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StopRecordingResponse", proto: "bosdyn.api.graph_nav.recording_pb2.StopRecordingResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.error_waypoint_localized_id = ros_msg.error_waypoint_localized_id - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - if ros_msg.session_start_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.session_start_time, proto.session_start_time) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_create_waypoint_request(proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointRequest", ros_msg: "bosdyn_msgs.msgs.CreateWaypointRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.waypoint_name = proto.waypoint_name - convert_proto_to_bosdyn_msgs_recording_environment(proto.recording_environment, ros_msg.recording_environment) - ros_msg.recording_environment_is_set = proto.HasField("recording_environment") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.require_fiducials = [] - for _item in proto.require_fiducials: - ros_msg.require_fiducials.append(_item) - from bosdyn_msgs.msg import WorldObject - ros_msg.world_objects = [] - for _item in proto.world_objects: - ros_msg.world_objects.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.world_objects[-1]) - - -def convert_bosdyn_msgs_create_waypoint_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateWaypointRequest", proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.waypoint_name = ros_msg.waypoint_name - if ros_msg.recording_environment_is_set: - convert_bosdyn_msgs_recording_environment_to_proto(ros_msg.recording_environment, proto.recording_environment) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - del proto.require_fiducials[:] - for _item in ros_msg.require_fiducials: - proto.require_fiducials.append(_item) - del proto.world_objects[:] - for _item in ros_msg.world_objects: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.world_objects.add()) - - -def convert_proto_to_bosdyn_msgs_create_waypoint_response_status(proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointResponse.Status", ros_msg: "bosdyn_msgs.msgs.CreateWaypointResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_create_waypoint_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateWaypointResponseStatus", proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_create_waypoint_response(proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointResponse", ros_msg: "bosdyn_msgs.msgs.CreateWaypointResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_waypoint(proto.created_waypoint, ros_msg.created_waypoint) - ros_msg.created_waypoint_is_set = proto.HasField("created_waypoint") - convert_proto_to_bosdyn_msgs_edge(proto.created_edge, ros_msg.created_edge) - ros_msg.created_edge_is_set = proto.HasField("created_edge") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.missing_fiducials = [] - for _item in proto.missing_fiducials: - ros_msg.missing_fiducials.append(_item) - ros_msg.bad_pose_fiducials = [] - for _item in proto.bad_pose_fiducials: - ros_msg.bad_pose_fiducials.append(_item) - ros_msg.license_status.value = proto.license_status - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_create_waypoint_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateWaypointResponse", proto: "bosdyn.api.graph_nav.recording_pb2.CreateWaypointResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.created_waypoint_is_set: - convert_bosdyn_msgs_waypoint_to_proto(ros_msg.created_waypoint, proto.created_waypoint) - if ros_msg.created_edge_is_set: - convert_bosdyn_msgs_edge_to_proto(ros_msg.created_edge, proto.created_edge) - proto.status = ros_msg.status.value - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - del proto.missing_fiducials[:] - for _item in ros_msg.missing_fiducials: - proto.missing_fiducials.append(_item) - del proto.bad_pose_fiducials[:] - for _item in ros_msg.bad_pose_fiducials: - proto.bad_pose_fiducials.append(_item) - proto.license_status = ros_msg.license_status.value - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_create_edge_request(proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeRequest", ros_msg: "bosdyn_msgs.msgs.CreateEdgeRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_edge(proto.edge, ros_msg.edge) - ros_msg.edge_is_set = proto.HasField("edge") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_create_edge_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateEdgeRequest", proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.edge_is_set: - convert_bosdyn_msgs_edge_to_proto(ros_msg.edge, proto.edge) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_create_edge_response_status(proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeResponse.Status", ros_msg: "bosdyn_msgs.msgs.CreateEdgeResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_create_edge_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateEdgeResponseStatus", proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_create_edge_response(proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeResponse", ros_msg: "bosdyn_msgs.msgs.CreateEdgeResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_edge(proto.error_existing_edge, ros_msg.error_existing_edge) - ros_msg.error_existing_edge_is_set = proto.HasField("error_existing_edge") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_create_edge_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CreateEdgeResponse", proto: "bosdyn.api.graph_nav.recording_pb2.CreateEdgeResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.error_existing_edge_is_set: - convert_bosdyn_msgs_edge_to_proto(ros_msg.error_existing_edge, proto.error_existing_edge) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_get_record_status_request(proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetRecordStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_record_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRecordStatusRequest", proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_record_status_response_map_state(proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse.MapState", ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponseMapState") -> None: - pass - - -def convert_bosdyn_msgs_get_record_status_response_map_state_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponseMapState", proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse.MapState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_record_status_response_status(proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_record_status_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponseStatus", proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_record_status_response(proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.is_recording = proto.is_recording - convert_proto_to_bosdyn_msgs_recording_environment(proto.recording_environment, ros_msg.recording_environment) - ros_msg.recording_environment_is_set = proto.HasField("recording_environment") - ros_msg.map_state.value = proto.map_state - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_robot_impaired_state(proto.impaired_state, ros_msg.impaired_state) - ros_msg.impaired_state_is_set = proto.HasField("impaired_state") - convert_proto_to_builtin_interfaces_time(proto.session_start_time, ros_msg.session_start_time) - ros_msg.session_start_time_is_set = proto.HasField("session_start_time") - convert_proto_to_bosdyn_msgs_map_stats(proto.map_stats, ros_msg.map_stats) - ros_msg.map_stats_is_set = proto.HasField("map_stats") - - -def convert_bosdyn_msgs_get_record_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRecordStatusResponse", proto: "bosdyn.api.graph_nav.recording_pb2.GetRecordStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.is_recording = ros_msg.is_recording - if ros_msg.recording_environment_is_set: - convert_bosdyn_msgs_recording_environment_to_proto(ros_msg.recording_environment, proto.recording_environment) - proto.map_state = ros_msg.map_state.value - proto.status = ros_msg.status.value - if ros_msg.impaired_state_is_set: - convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg.impaired_state, proto.impaired_state) - if ros_msg.session_start_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.session_start_time, proto.session_start_time) - if ros_msg.map_stats_is_set: - convert_bosdyn_msgs_map_stats_to_proto(ros_msg.map_stats, proto.map_stats) - - -def convert_proto_to_bosdyn_msgs_gripper_camera_param_request(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParamRequest", ros_msg: "bosdyn_msgs.msgs.GripperCameraParamRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_gripper_camera_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_gripper_camera_param_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraParamRequest", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParamRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_gripper_camera_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_gripper_camera_param_response(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParamResponse", ros_msg: "bosdyn_msgs.msgs.GripperCameraParamResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_gripper_camera_param_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraParamResponse", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParamResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_gripper_camera_get_param_request(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraGetParamRequest", ros_msg: "bosdyn_msgs.msgs.GripperCameraGetParamRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_gripper_camera_get_param_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraGetParamRequest", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraGetParamRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_gripper_camera_get_param_response(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraGetParamResponse", ros_msg: "bosdyn_msgs.msgs.GripperCameraGetParamResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_gripper_camera_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_gripper_camera_get_param_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraGetParamResponse", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraGetParamResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_gripper_camera_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_gripper_camera_params_camera_mode(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams.CameraMode", ros_msg: "bosdyn_msgs.msgs.GripperCameraParamsCameraMode") -> None: - pass - - -def convert_bosdyn_msgs_gripper_camera_params_camera_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraParamsCameraMode", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams.CameraMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_gripper_camera_params_led_mode(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams.LedMode", ros_msg: "bosdyn_msgs.msgs.GripperCameraParamsLedMode") -> None: - pass - - -def convert_bosdyn_msgs_gripper_camera_params_led_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraParamsLedMode", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams.LedMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_gripper_camera_params(proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams", ros_msg: "bosdyn_msgs.msgs.GripperCameraParams") -> None: - ros_msg.camera_mode.value = proto.camera_mode - ros_msg.brightness = proto.brightness.value - ros_msg.brightness_is_set = proto.HasField("brightness") - ros_msg.contrast = proto.contrast.value - ros_msg.contrast_is_set = proto.HasField("contrast") - ros_msg.saturation = proto.saturation.value - ros_msg.saturation_is_set = proto.HasField("saturation") - ros_msg.gain = proto.gain.value - ros_msg.gain_is_set = proto.HasField("gain") - ros_msg.exposure_auto = proto.exposure_auto.value - ros_msg.exposure_auto_is_set = proto.HasField("exposure_auto") - ros_msg.exposure_absolute = proto.exposure_absolute.value - ros_msg.exposure_absolute_is_set = proto.HasField("exposure_absolute") - convert_proto_to_bosdyn_msgs_roi_parameters(proto.exposure_roi, ros_msg.exposure_roi) - ros_msg.exposure_roi_is_set = proto.HasField("exposure_roi") - ros_msg.focus_auto = proto.focus_auto.value - ros_msg.focus_auto_is_set = proto.HasField("focus_auto") - ros_msg.focus_absolute = proto.focus_absolute.value - ros_msg.focus_absolute_is_set = proto.HasField("focus_absolute") - convert_proto_to_bosdyn_msgs_roi_parameters(proto.focus_roi, ros_msg.focus_roi) - ros_msg.focus_roi_is_set = proto.HasField("focus_roi") - ros_msg.draw_focus_roi_rectangle = proto.draw_focus_roi_rectangle.value - ros_msg.draw_focus_roi_rectangle_is_set = proto.HasField("draw_focus_roi_rectangle") - ros_msg.hdr.value = proto.hdr - ros_msg.led_mode.value = proto.led_mode - ros_msg.led_torch_brightness = proto.led_torch_brightness.value - ros_msg.led_torch_brightness_is_set = proto.HasField("led_torch_brightness") - ros_msg.white_balance_temperature_auto = proto.white_balance_temperature_auto.value - ros_msg.white_balance_temperature_auto_is_set = proto.HasField("white_balance_temperature_auto") - ros_msg.gamma = proto.gamma.value - ros_msg.gamma_is_set = proto.HasField("gamma") - ros_msg.white_balance_temperature = proto.white_balance_temperature.value - ros_msg.white_balance_temperature_is_set = proto.HasField("white_balance_temperature") - ros_msg.sharpness = proto.sharpness.value - ros_msg.sharpness_is_set = proto.HasField("sharpness") - - -def convert_bosdyn_msgs_gripper_camera_params_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCameraParams", proto: "bosdyn.api.gripper_camera_param_pb2.GripperCameraParams") -> None: - proto.Clear() - proto.camera_mode = ros_msg.camera_mode.value - if ros_msg.brightness_is_set: - convert_float32_to_proto(ros_msg.brightness, proto.brightness) - if ros_msg.contrast_is_set: - convert_float32_to_proto(ros_msg.contrast, proto.contrast) - if ros_msg.saturation_is_set: - convert_float32_to_proto(ros_msg.saturation, proto.saturation) - if ros_msg.gain_is_set: - convert_float32_to_proto(ros_msg.gain, proto.gain) - if ros_msg.exposure_auto_is_set: - convert_bool_to_proto(ros_msg.exposure_auto, proto.exposure_auto) - if ros_msg.exposure_absolute_is_set: - convert_float32_to_proto(ros_msg.exposure_absolute, proto.exposure_absolute) - if ros_msg.exposure_roi_is_set: - convert_bosdyn_msgs_roi_parameters_to_proto(ros_msg.exposure_roi, proto.exposure_roi) - if ros_msg.focus_auto_is_set: - convert_bool_to_proto(ros_msg.focus_auto, proto.focus_auto) - if ros_msg.focus_absolute_is_set: - convert_float32_to_proto(ros_msg.focus_absolute, proto.focus_absolute) - if ros_msg.focus_roi_is_set: - convert_bosdyn_msgs_roi_parameters_to_proto(ros_msg.focus_roi, proto.focus_roi) - if ros_msg.draw_focus_roi_rectangle_is_set: - convert_bool_to_proto(ros_msg.draw_focus_roi_rectangle, proto.draw_focus_roi_rectangle) - proto.hdr = ros_msg.hdr.value - proto.led_mode = ros_msg.led_mode.value - if ros_msg.led_torch_brightness_is_set: - convert_float32_to_proto(ros_msg.led_torch_brightness, proto.led_torch_brightness) - if ros_msg.white_balance_temperature_auto_is_set: - convert_bool_to_proto(ros_msg.white_balance_temperature_auto, proto.white_balance_temperature_auto) - if ros_msg.gamma_is_set: - convert_float32_to_proto(ros_msg.gamma, proto.gamma) - if ros_msg.white_balance_temperature_is_set: - convert_float32_to_proto(ros_msg.white_balance_temperature, proto.white_balance_temperature) - if ros_msg.sharpness_is_set: - convert_float32_to_proto(ros_msg.sharpness, proto.sharpness) - - -def convert_proto_to_bosdyn_msgs_hdr_parameters(proto: "bosdyn.api.gripper_camera_param_pb2.HdrParameters", ros_msg: "bosdyn_msgs.msgs.HdrParameters") -> None: - pass - - -def convert_bosdyn_msgs_hdr_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.HdrParameters", proto: "bosdyn.api.gripper_camera_param_pb2.HdrParameters") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_roi_parameters_roi_window_size(proto: "bosdyn.api.gripper_camera_param_pb2.RoiParameters.RoiWindowSize", ros_msg: "bosdyn_msgs.msgs.RoiParametersRoiWindowSize") -> None: - pass - - -def convert_bosdyn_msgs_roi_parameters_roi_window_size_to_proto(ros_msg: "bosdyn_msgs.msgs.RoiParametersRoiWindowSize", proto: "bosdyn.api.gripper_camera_param_pb2.RoiParameters.RoiWindowSize") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_roi_parameters(proto: "bosdyn.api.gripper_camera_param_pb2.RoiParameters", ros_msg: "bosdyn_msgs.msgs.RoiParameters") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.roi_percentage_in_image, ros_msg.roi_percentage_in_image) - ros_msg.roi_percentage_in_image_is_set = proto.HasField("roi_percentage_in_image") - ros_msg.window_size.value = proto.window_size - - -def convert_bosdyn_msgs_roi_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.RoiParameters", proto: "bosdyn.api.gripper_camera_param_pb2.RoiParameters") -> None: - proto.Clear() - if ros_msg.roi_percentage_in_image_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.roi_percentage_in_image, proto.roi_percentage_in_image) - proto.window_size = ros_msg.window_size.value - - -def convert_proto_to_bosdyn_msgs_gripper_command_request_one_of_command(proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Request", ros_msg: "bosdyn_msgs.msgs.GripperCommandRequestOneOfCommand") -> None: - if proto.HasField("claw_gripper_command"): - ros_msg.command_choice = ros_msg.COMMAND_CLAW_GRIPPER_COMMAND_SET - convert_proto_to_bosdyn_msgs_claw_gripper_command_request(proto.claw_gripper_command, ros_msg.claw_gripper_command) - - -def convert_bosdyn_msgs_gripper_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCommandRequestOneOfCommand", proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_CLAW_GRIPPER_COMMAND_SET: - convert_bosdyn_msgs_claw_gripper_command_request_to_proto(ros_msg.claw_gripper_command, proto.claw_gripper_command) - - -def convert_proto_to_bosdyn_msgs_gripper_command_request(proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Request", ros_msg: "bosdyn_msgs.msgs.GripperCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_gripper_command_request_one_of_command(proto, ros_msg.command) - - -def convert_bosdyn_msgs_gripper_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCommandRequest", proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_gripper_command_request_one_of_command_to_proto(ros_msg.command, proto) - - -def convert_proto_to_bosdyn_msgs_gripper_command_feedback_one_of_command(proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.GripperCommandFeedbackOneOfCommand") -> None: - if proto.HasField("claw_gripper_feedback"): - ros_msg.command_choice = ros_msg.COMMAND_CLAW_GRIPPER_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_claw_gripper_command_feedback(proto.claw_gripper_feedback, ros_msg.claw_gripper_feedback) - - -def convert_bosdyn_msgs_gripper_command_feedback_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCommandFeedbackOneOfCommand", proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Feedback") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_CLAW_GRIPPER_FEEDBACK_SET: - convert_bosdyn_msgs_claw_gripper_command_feedback_to_proto(ros_msg.claw_gripper_feedback, proto.claw_gripper_feedback) - - -def convert_proto_to_bosdyn_msgs_gripper_command_feedback(proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.GripperCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_gripper_command_feedback_one_of_command(proto, ros_msg.command) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_gripper_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCommandFeedback", proto: "bosdyn.api.gripper_command_pb2.GripperCommand.Feedback") -> None: - proto.Clear() - convert_bosdyn_msgs_gripper_command_feedback_one_of_command_to_proto(ros_msg.command, proto) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_gripper_command(proto: "bosdyn.api.gripper_command_pb2.GripperCommand", ros_msg: "bosdyn_msgs.msgs.GripperCommand") -> None: - pass - - -def convert_bosdyn_msgs_gripper_command_to_proto(ros_msg: "bosdyn_msgs.msgs.GripperCommand", proto: "bosdyn.api.gripper_command_pb2.GripperCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_claw_gripper_command_request(proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Request", ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_scalar_trajectory(proto.trajectory, ros_msg.trajectory) - ros_msg.trajectory_is_set = proto.HasField("trajectory") - ros_msg.maximum_open_close_velocity = proto.maximum_open_close_velocity.value - ros_msg.maximum_open_close_velocity_is_set = proto.HasField("maximum_open_close_velocity") - ros_msg.maximum_open_close_acceleration = proto.maximum_open_close_acceleration.value - ros_msg.maximum_open_close_acceleration_is_set = proto.HasField("maximum_open_close_acceleration") - ros_msg.maximum_torque = proto.maximum_torque.value - ros_msg.maximum_torque_is_set = proto.HasField("maximum_torque") - ros_msg.disable_force_on_contact = proto.disable_force_on_contact - - -def convert_bosdyn_msgs_claw_gripper_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandRequest", proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Request") -> None: - proto.Clear() - if ros_msg.trajectory_is_set: - convert_bosdyn_msgs_scalar_trajectory_to_proto(ros_msg.trajectory, proto.trajectory) - if ros_msg.maximum_open_close_velocity_is_set: - convert_float64_to_proto(ros_msg.maximum_open_close_velocity, proto.maximum_open_close_velocity) - if ros_msg.maximum_open_close_acceleration_is_set: - convert_float64_to_proto(ros_msg.maximum_open_close_acceleration, proto.maximum_open_close_acceleration) - if ros_msg.maximum_torque_is_set: - convert_float64_to_proto(ros_msg.maximum_torque, proto.maximum_torque) - proto.disable_force_on_contact = ros_msg.disable_force_on_contact - - -def convert_proto_to_bosdyn_msgs_claw_gripper_command_feedback_status(proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_claw_gripper_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandFeedbackStatus", proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_claw_gripper_command_feedback(proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandFeedback") -> None: - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_claw_gripper_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.ClawGripperCommandFeedback", proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_claw_gripper_command(proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand", ros_msg: "bosdyn_msgs.msgs.ClawGripperCommand") -> None: - pass - - -def convert_bosdyn_msgs_claw_gripper_command_to_proto(ros_msg: "bosdyn_msgs.msgs.ClawGripperCommand", proto: "bosdyn.api.gripper_command_pb2.ClawGripperCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_request_header(proto: "bosdyn.api.header_pb2.RequestHeader", ros_msg: "bosdyn_msgs.msgs.RequestHeader") -> None: - convert_proto_to_builtin_interfaces_time(proto.request_timestamp, ros_msg.request_timestamp) - ros_msg.request_timestamp_is_set = proto.HasField("request_timestamp") - ros_msg.client_name = proto.client_name - ros_msg.disable_rpc_logging = proto.disable_rpc_logging - - -def convert_bosdyn_msgs_request_header_to_proto(ros_msg: "bosdyn_msgs.msgs.RequestHeader", proto: "bosdyn.api.header_pb2.RequestHeader") -> None: - proto.Clear() - if ros_msg.request_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.request_timestamp, proto.request_timestamp) - proto.client_name = ros_msg.client_name - proto.disable_rpc_logging = ros_msg.disable_rpc_logging - - -def convert_proto_to_bosdyn_msgs_common_error_code(proto: "bosdyn.api.header_pb2.CommonError.Code", ros_msg: "bosdyn_msgs.msgs.CommonErrorCode") -> None: - pass - - -def convert_bosdyn_msgs_common_error_code_to_proto(ros_msg: "bosdyn_msgs.msgs.CommonErrorCode", proto: "bosdyn.api.header_pb2.CommonError.Code") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_common_error(proto: "bosdyn.api.header_pb2.CommonError", ros_msg: "bosdyn_msgs.msgs.CommonError") -> None: - ros_msg.code.value = proto.code - ros_msg.message = proto.message - - -def convert_bosdyn_msgs_common_error_to_proto(ros_msg: "bosdyn_msgs.msgs.CommonError", proto: "bosdyn.api.header_pb2.CommonError") -> None: - proto.Clear() - proto.code = ros_msg.code.value - proto.message = ros_msg.message - - -def convert_proto_to_bosdyn_msgs_response_header(proto: "bosdyn.api.header_pb2.ResponseHeader", ros_msg: "bosdyn_msgs.msgs.ResponseHeader") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.request_header, ros_msg.request_header) - ros_msg.request_header_is_set = proto.HasField("request_header") - convert_proto_to_builtin_interfaces_time(proto.request_received_timestamp, ros_msg.request_received_timestamp) - ros_msg.request_received_timestamp_is_set = proto.HasField("request_received_timestamp") - convert_proto_to_builtin_interfaces_time(proto.response_timestamp, ros_msg.response_timestamp) - ros_msg.response_timestamp_is_set = proto.HasField("response_timestamp") - convert_proto_to_bosdyn_msgs_common_error(proto.error, ros_msg.error) - ros_msg.error_is_set = proto.HasField("error") - - -def convert_bosdyn_msgs_response_header_to_proto(ros_msg: "bosdyn_msgs.msgs.ResponseHeader", proto: "bosdyn.api.header_pb2.ResponseHeader") -> None: - proto.Clear() - if ros_msg.request_header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.request_header, proto.request_header) - if ros_msg.request_received_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.request_received_timestamp, proto.request_received_timestamp) - if ros_msg.response_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.response_timestamp, proto.response_timestamp) - if ros_msg.error_is_set: - convert_bosdyn_msgs_common_error_to_proto(ros_msg.error, proto.error) - - -def convert_proto_to_bosdyn_msgs_image_format(proto: "bosdyn.api.image_pb2.Image.Format", ros_msg: "bosdyn_msgs.msgs.ImageFormat") -> None: - pass - - -def convert_bosdyn_msgs_image_format_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageFormat", proto: "bosdyn.api.image_pb2.Image.Format") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_image_pixel_format(proto: "bosdyn.api.image_pb2.Image.PixelFormat", ros_msg: "bosdyn_msgs.msgs.ImagePixelFormat") -> None: - pass - - -def convert_bosdyn_msgs_image_pixel_format_to_proto(ros_msg: "bosdyn_msgs.msgs.ImagePixelFormat", proto: "bosdyn.api.image_pb2.Image.PixelFormat") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_image(proto: "bosdyn.api.image_pb2.Image", ros_msg: "bosdyn_msgs.msgs.Image") -> None: - ros_msg.cols = proto.cols - ros_msg.rows = proto.rows - ros_msg.data = proto.data - ros_msg.format.value = proto.format - ros_msg.pixel_format.value = proto.pixel_format - - -def convert_bosdyn_msgs_image_to_proto(ros_msg: "bosdyn_msgs.msgs.Image", proto: "bosdyn.api.image_pb2.Image") -> None: - proto.Clear() - proto.cols = ros_msg.cols - proto.rows = ros_msg.rows - proto.data = ros_msg.data - proto.format = ros_msg.format.value - proto.pixel_format = ros_msg.pixel_format.value - - -def convert_proto_to_bosdyn_msgs_capture_parameters(proto: "bosdyn.api.image_pb2.CaptureParameters", ros_msg: "bosdyn_msgs.msgs.CaptureParameters") -> None: - convert_proto_to_builtin_interfaces_duration(proto.exposure_duration, ros_msg.exposure_duration) - ros_msg.exposure_duration_is_set = proto.HasField("exposure_duration") - ros_msg.gain = proto.gain - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_capture_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.CaptureParameters", proto: "bosdyn.api.image_pb2.CaptureParameters") -> None: - proto.Clear() - if ros_msg.exposure_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.exposure_duration, proto.exposure_duration) - proto.gain = ros_msg.gain - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_image_capture(proto: "bosdyn.api.image_pb2.ImageCapture", ros_msg: "bosdyn_msgs.msgs.ImageCapture") -> None: - convert_proto_to_builtin_interfaces_time(proto.acquisition_time, ros_msg.acquisition_time) - ros_msg.acquisition_time_is_set = proto.HasField("acquisition_time") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - ros_msg.frame_name_image_sensor = proto.frame_name_image_sensor - convert_proto_to_bosdyn_msgs_image(proto.image, ros_msg.image) - ros_msg.image_is_set = proto.HasField("image") - convert_proto_to_bosdyn_msgs_capture_parameters(proto.capture_params, ros_msg.capture_params) - ros_msg.capture_params_is_set = proto.HasField("capture_params") - - -def convert_bosdyn_msgs_image_capture_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageCapture", proto: "bosdyn.api.image_pb2.ImageCapture") -> None: - proto.Clear() - if ros_msg.acquisition_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.acquisition_time, proto.acquisition_time) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - proto.frame_name_image_sensor = ros_msg.frame_name_image_sensor - if ros_msg.image_is_set: - convert_bosdyn_msgs_image_to_proto(ros_msg.image, proto.image) - if ros_msg.capture_params_is_set: - convert_bosdyn_msgs_capture_parameters_to_proto(ros_msg.capture_params, proto.capture_params) - - -def convert_proto_to_bosdyn_msgs_image_source_pinhole_model_camera_intrinsics(proto: "bosdyn.api.image_pb2.ImageSource.PinholeModel.CameraIntrinsics", ros_msg: "bosdyn_msgs.msgs.ImageSourcePinholeModelCameraIntrinsics") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.focal_length, ros_msg.focal_length) - ros_msg.focal_length_is_set = proto.HasField("focal_length") - convert_proto_to_bosdyn_msgs_vec2(proto.principal_point, ros_msg.principal_point) - ros_msg.principal_point_is_set = proto.HasField("principal_point") - convert_proto_to_bosdyn_msgs_vec2(proto.skew, ros_msg.skew) - ros_msg.skew_is_set = proto.HasField("skew") - - -def convert_bosdyn_msgs_image_source_pinhole_model_camera_intrinsics_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourcePinholeModelCameraIntrinsics", proto: "bosdyn.api.image_pb2.ImageSource.PinholeModel.CameraIntrinsics") -> None: - proto.Clear() - if ros_msg.focal_length_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.focal_length, proto.focal_length) - if ros_msg.principal_point_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.principal_point, proto.principal_point) - if ros_msg.skew_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.skew, proto.skew) - - -def convert_proto_to_bosdyn_msgs_image_source_pinhole_model(proto: "bosdyn.api.image_pb2.ImageSource.PinholeModel", ros_msg: "bosdyn_msgs.msgs.ImageSourcePinholeModel") -> None: - convert_proto_to_bosdyn_msgs_image_source_pinhole_model_camera_intrinsics(proto.intrinsics, ros_msg.intrinsics) - ros_msg.intrinsics_is_set = proto.HasField("intrinsics") - - -def convert_bosdyn_msgs_image_source_pinhole_model_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourcePinholeModel", proto: "bosdyn.api.image_pb2.ImageSource.PinholeModel") -> None: - proto.Clear() - if ros_msg.intrinsics_is_set: - convert_bosdyn_msgs_image_source_pinhole_model_camera_intrinsics_to_proto(ros_msg.intrinsics, proto.intrinsics) - - -def convert_proto_to_bosdyn_msgs_image_source_one_of_camera_models(proto: "bosdyn.api.image_pb2.ImageSource", ros_msg: "bosdyn_msgs.msgs.ImageSourceOneOfCameraModels") -> None: - if proto.HasField("pinhole"): - ros_msg.camera_models_choice = ros_msg.CAMERA_MODELS_PINHOLE_SET - convert_proto_to_bosdyn_msgs_image_source_pinhole_model(proto.pinhole, ros_msg.pinhole) - - -def convert_bosdyn_msgs_image_source_one_of_camera_models_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourceOneOfCameraModels", proto: "bosdyn.api.image_pb2.ImageSource") -> None: - proto.ClearField("camera_models") - if ros_msg.camera_models_choice == ros_msg.CAMERA_MODELS_PINHOLE_SET: - convert_bosdyn_msgs_image_source_pinhole_model_to_proto(ros_msg.pinhole, proto.pinhole) - - -def convert_proto_to_bosdyn_msgs_image_source_image_type(proto: "bosdyn.api.image_pb2.ImageSource.ImageType", ros_msg: "bosdyn_msgs.msgs.ImageSourceImageType") -> None: - pass - - -def convert_bosdyn_msgs_image_source_image_type_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourceImageType", proto: "bosdyn.api.image_pb2.ImageSource.ImageType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_image_source(proto: "bosdyn.api.image_pb2.ImageSource", ros_msg: "bosdyn_msgs.msgs.ImageSource") -> None: - ros_msg.name = proto.name - ros_msg.cols = proto.cols - ros_msg.rows = proto.rows - ros_msg.depth_scale = proto.depth_scale - convert_proto_to_bosdyn_msgs_image_source_one_of_camera_models(proto, ros_msg.camera_models) - ros_msg.image_type.value = proto.image_type - from bosdyn_msgs.msg import ImagePixelFormat - ros_msg.pixel_formats = [] - for _item in proto.pixel_formats: - ros_msg.pixel_formats.append(ImagePixelFormat()) - ros_msg.pixel_formats[-1].value = _item - from bosdyn_msgs.msg import ImageFormat - ros_msg.image_formats = [] - for _item in proto.image_formats: - ros_msg.image_formats.append(ImageFormat()) - ros_msg.image_formats[-1].value = _item - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_image_source_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSource", proto: "bosdyn.api.image_pb2.ImageSource") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.cols = ros_msg.cols - proto.rows = ros_msg.rows - proto.depth_scale = ros_msg.depth_scale - convert_bosdyn_msgs_image_source_one_of_camera_models_to_proto(ros_msg.camera_models, proto) - proto.image_type = ros_msg.image_type.value - del proto.pixel_formats[:] - for _item in ros_msg.pixel_formats: - proto.pixel_formats.append(_item.value) - del proto.image_formats[:] - for _item in ros_msg.image_formats: - proto.image_formats.append(_item.value) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_list_image_sources_request(proto: "bosdyn.api.image_pb2.ListImageSourcesRequest", ros_msg: "bosdyn_msgs.msgs.ListImageSourcesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_image_sources_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListImageSourcesRequest", proto: "bosdyn.api.image_pb2.ListImageSourcesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_image_sources_response(proto: "bosdyn.api.image_pb2.ListImageSourcesResponse", ros_msg: "bosdyn_msgs.msgs.ListImageSourcesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ImageSource - ros_msg.image_sources = [] - for _item in proto.image_sources: - ros_msg.image_sources.append(ImageSource()) - convert_proto_to_bosdyn_msgs_image_source(_item, ros_msg.image_sources[-1]) - - -def convert_bosdyn_msgs_list_image_sources_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListImageSourcesResponse", proto: "bosdyn.api.image_pb2.ListImageSourcesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.image_sources[:] - for _item in ros_msg.image_sources: - convert_bosdyn_msgs_image_source_to_proto(_item, proto.image_sources.add()) - - -def convert_proto_to_bosdyn_msgs_image_request(proto: "bosdyn.api.image_pb2.ImageRequest", ros_msg: "bosdyn_msgs.msgs.ImageRequest") -> None: - ros_msg.image_source_name = proto.image_source_name - ros_msg.quality_percent = proto.quality_percent - ros_msg.image_format.value = proto.image_format - ros_msg.resize_ratio = proto.resize_ratio - ros_msg.pixel_format.value = proto.pixel_format - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_image_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageRequest", proto: "bosdyn.api.image_pb2.ImageRequest") -> None: - proto.Clear() - proto.image_source_name = ros_msg.image_source_name - proto.quality_percent = ros_msg.quality_percent - proto.image_format = ros_msg.image_format.value - proto.resize_ratio = ros_msg.resize_ratio - proto.pixel_format = ros_msg.pixel_format.value - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_get_image_request(proto: "bosdyn.api.image_pb2.GetImageRequest", ros_msg: "bosdyn_msgs.msgs.GetImageRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ImageRequest - ros_msg.image_requests = [] - for _item in proto.image_requests: - ros_msg.image_requests.append(ImageRequest()) - convert_proto_to_bosdyn_msgs_image_request(_item, ros_msg.image_requests[-1]) - - -def convert_bosdyn_msgs_get_image_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetImageRequest", proto: "bosdyn.api.image_pb2.GetImageRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.image_requests[:] - for _item in ros_msg.image_requests: - convert_bosdyn_msgs_image_request_to_proto(_item, proto.image_requests.add()) - - -def convert_proto_to_bosdyn_msgs_image_response_status(proto: "bosdyn.api.image_pb2.ImageResponse.Status", ros_msg: "bosdyn_msgs.msgs.ImageResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_image_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageResponseStatus", proto: "bosdyn.api.image_pb2.ImageResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_image_response(proto: "bosdyn.api.image_pb2.ImageResponse", ros_msg: "bosdyn_msgs.msgs.ImageResponse") -> None: - convert_proto_to_bosdyn_msgs_image_capture(proto.shot, ros_msg.shot) - ros_msg.shot_is_set = proto.HasField("shot") - convert_proto_to_bosdyn_msgs_image_source(proto.source, ros_msg.source) - ros_msg.source_is_set = proto.HasField("source") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - - -def convert_bosdyn_msgs_image_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageResponse", proto: "bosdyn.api.image_pb2.ImageResponse") -> None: - proto.Clear() - if ros_msg.shot_is_set: - convert_bosdyn_msgs_image_capture_to_proto(ros_msg.shot, proto.shot) - if ros_msg.source_is_set: - convert_bosdyn_msgs_image_source_to_proto(ros_msg.source, proto.source) - proto.status = ros_msg.status.value - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - - -def convert_proto_to_bosdyn_msgs_image_capture_and_source(proto: "bosdyn.api.image_pb2.ImageCaptureAndSource", ros_msg: "bosdyn_msgs.msgs.ImageCaptureAndSource") -> None: - convert_proto_to_bosdyn_msgs_image_capture(proto.shot, ros_msg.shot) - ros_msg.shot_is_set = proto.HasField("shot") - convert_proto_to_bosdyn_msgs_image_source(proto.source, ros_msg.source) - ros_msg.source_is_set = proto.HasField("source") - ros_msg.image_service = proto.image_service - - -def convert_bosdyn_msgs_image_capture_and_source_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageCaptureAndSource", proto: "bosdyn.api.image_pb2.ImageCaptureAndSource") -> None: - proto.Clear() - if ros_msg.shot_is_set: - convert_bosdyn_msgs_image_capture_to_proto(ros_msg.shot, proto.shot) - if ros_msg.source_is_set: - convert_bosdyn_msgs_image_source_to_proto(ros_msg.source, proto.source) - proto.image_service = ros_msg.image_service - - -def convert_proto_to_bosdyn_msgs_get_image_response(proto: "bosdyn.api.image_pb2.GetImageResponse", ros_msg: "bosdyn_msgs.msgs.GetImageResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ImageResponse - ros_msg.image_responses = [] - for _item in proto.image_responses: - ros_msg.image_responses.append(ImageResponse()) - convert_proto_to_bosdyn_msgs_image_response(_item, ros_msg.image_responses[-1]) - - -def convert_bosdyn_msgs_get_image_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetImageResponse", proto: "bosdyn.api.image_pb2.GetImageResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.image_responses[:] - for _item in ros_msg.image_responses: - convert_bosdyn_msgs_image_response_to_proto(_item, proto.image_responses.add()) - - -def convert_proto_to_bosdyn_msgs_rectangle_i(proto: "bosdyn.api.image_geometry_pb2.RectangleI", ros_msg: "bosdyn_msgs.msgs.RectangleI") -> None: - ros_msg.x = proto.x - ros_msg.y = proto.y - ros_msg.cols = proto.cols - ros_msg.rows = proto.rows - - -def convert_bosdyn_msgs_rectangle_i_to_proto(ros_msg: "bosdyn_msgs.msgs.RectangleI", proto: "bosdyn.api.image_geometry_pb2.RectangleI") -> None: - proto.Clear() - proto.x = ros_msg.x - proto.y = ros_msg.y - proto.cols = ros_msg.cols - proto.rows = ros_msg.rows - - -def convert_proto_to_bosdyn_msgs_area_i_one_of_geometry(proto: "bosdyn.api.image_geometry_pb2.AreaI", ros_msg: "bosdyn_msgs.msgs.AreaIOneOfGeometry") -> None: - if proto.HasField("rectangle"): - ros_msg.geometry_choice = ros_msg.GEOMETRY_RECTANGLE_SET - convert_proto_to_bosdyn_msgs_rectangle_i(proto.rectangle, ros_msg.rectangle) - - -def convert_bosdyn_msgs_area_i_one_of_geometry_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaIOneOfGeometry", proto: "bosdyn.api.image_geometry_pb2.AreaI") -> None: - proto.ClearField("geometry") - if ros_msg.geometry_choice == ros_msg.GEOMETRY_RECTANGLE_SET: - convert_bosdyn_msgs_rectangle_i_to_proto(ros_msg.rectangle, proto.rectangle) - - -def convert_proto_to_bosdyn_msgs_area_i(proto: "bosdyn.api.image_geometry_pb2.AreaI", ros_msg: "bosdyn_msgs.msgs.AreaI") -> None: - convert_proto_to_bosdyn_msgs_area_i_one_of_geometry(proto, ros_msg.geometry) - - -def convert_bosdyn_msgs_area_i_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaI", proto: "bosdyn.api.image_geometry_pb2.AreaI") -> None: - proto.Clear() - convert_bosdyn_msgs_area_i_one_of_geometry_to_proto(ros_msg.geometry, proto) - - -def convert_proto_to_bosdyn_msgs_ir_enable_disable_request_request(proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableRequest.Request", ros_msg: "bosdyn_msgs.msgs.IREnableDisableRequestRequest") -> None: - pass - - -def convert_bosdyn_msgs_ir_enable_disable_request_request_to_proto(ros_msg: "bosdyn_msgs.msgs.IREnableDisableRequestRequest", proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableRequest.Request") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ir_enable_disable_request(proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableRequest", ros_msg: "bosdyn_msgs.msgs.IREnableDisableRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.request.value = proto.request - - -def convert_bosdyn_msgs_ir_enable_disable_request_to_proto(ros_msg: "bosdyn_msgs.msgs.IREnableDisableRequest", proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.request = ros_msg.request.value - - -def convert_proto_to_bosdyn_msgs_ir_enable_disable_response(proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableResponse", ros_msg: "bosdyn_msgs.msgs.IREnableDisableResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_ir_enable_disable_response_to_proto(ros_msg: "bosdyn_msgs.msgs.IREnableDisableResponse", proto: "bosdyn.api.ir_enable_disable_pb2.IREnableDisableResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_policy(proto: "bosdyn.api.keepalive.keepalive_pb2.Policy", ros_msg: "bosdyn_msgs.msgs.Policy") -> None: - ros_msg.name = proto.name - from bosdyn_msgs.msg import ActionAfter - ros_msg.actions = [] - for _item in proto.actions: - ros_msg.actions.append(ActionAfter()) - convert_proto_to_bosdyn_msgs_action_after(_item, ros_msg.actions[-1]) - from bosdyn_msgs.msg import Lease - ros_msg.associated_leases = [] - for _item in proto.associated_leases: - ros_msg.associated_leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.associated_leases[-1]) - ros_msg.user_id = proto.user_id - - -def convert_bosdyn_msgs_policy_to_proto(ros_msg: "bosdyn_msgs.msgs.Policy", proto: "bosdyn.api.keepalive.keepalive_pb2.Policy") -> None: - proto.Clear() - proto.name = ros_msg.name - del proto.actions[:] - for _item in ros_msg.actions: - convert_bosdyn_msgs_action_after_to_proto(_item, proto.actions.add()) - del proto.associated_leases[:] - for _item in ros_msg.associated_leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.associated_leases.add()) - proto.user_id = ros_msg.user_id - - -def convert_proto_to_bosdyn_msgs_action_after_record_event(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.RecordEvent", ros_msg: "bosdyn_msgs.msgs.ActionAfterRecordEvent") -> None: - from bosdyn_msgs.msg import Event - ros_msg.events = [] - for _item in proto.events: - ros_msg.events.append(Event()) - convert_proto_to_bosdyn_msgs_event(_item, ros_msg.events[-1]) - - -def convert_bosdyn_msgs_action_after_record_event_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterRecordEvent", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.RecordEvent") -> None: - proto.Clear() - del proto.events[:] - for _item in ros_msg.events: - convert_bosdyn_msgs_event_to_proto(_item, proto.events.add()) - - -def convert_proto_to_bosdyn_msgs_action_after_auto_return(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.AutoReturn", ros_msg: "bosdyn_msgs.msgs.ActionAfterAutoReturn") -> None: - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_action_after_auto_return_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterAutoReturn", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.AutoReturn") -> None: - proto.Clear() - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.params_is_set: - convert_bosdyn_msgs_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_action_after_controlled_motors_off(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.ControlledMotorsOff", ros_msg: "bosdyn_msgs.msgs.ActionAfterControlledMotorsOff") -> None: - pass - - -def convert_bosdyn_msgs_action_after_controlled_motors_off_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterControlledMotorsOff", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.ControlledMotorsOff") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_action_after_immediate_robot_off(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.ImmediateRobotOff", ros_msg: "bosdyn_msgs.msgs.ActionAfterImmediateRobotOff") -> None: - pass - - -def convert_bosdyn_msgs_action_after_immediate_robot_off_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterImmediateRobotOff", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.ImmediateRobotOff") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_action_after_lease_stale(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.LeaseStale", ros_msg: "bosdyn_msgs.msgs.ActionAfterLeaseStale") -> None: - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - - -def convert_bosdyn_msgs_action_after_lease_stale_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterLeaseStale", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter.LeaseStale") -> None: - proto.Clear() - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - - -def convert_proto_to_bosdyn_msgs_action_after_one_of_action(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter", ros_msg: "bosdyn_msgs.msgs.ActionAfterOneOfAction") -> None: - if proto.HasField("record_event"): - ros_msg.action_choice = ros_msg.ACTION_RECORD_EVENT_SET - convert_proto_to_bosdyn_msgs_action_after_record_event(proto.record_event, ros_msg.record_event) - if proto.HasField("auto_return"): - ros_msg.action_choice = ros_msg.ACTION_AUTO_RETURN_SET - convert_proto_to_bosdyn_msgs_action_after_auto_return(proto.auto_return, ros_msg.auto_return) - if proto.HasField("controlled_motors_off"): - ros_msg.action_choice = ros_msg.ACTION_CONTROLLED_MOTORS_OFF_SET - convert_proto_to_bosdyn_msgs_action_after_controlled_motors_off(proto.controlled_motors_off, ros_msg.controlled_motors_off) - if proto.HasField("immediate_robot_off"): - ros_msg.action_choice = ros_msg.ACTION_IMMEDIATE_ROBOT_OFF_SET - convert_proto_to_bosdyn_msgs_action_after_immediate_robot_off(proto.immediate_robot_off, ros_msg.immediate_robot_off) - if proto.HasField("lease_stale"): - ros_msg.action_choice = ros_msg.ACTION_LEASE_STALE_SET - convert_proto_to_bosdyn_msgs_action_after_lease_stale(proto.lease_stale, ros_msg.lease_stale) - - -def convert_bosdyn_msgs_action_after_one_of_action_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfterOneOfAction", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter") -> None: - proto.ClearField("action") - if ros_msg.action_choice == ros_msg.ACTION_RECORD_EVENT_SET: - convert_bosdyn_msgs_action_after_record_event_to_proto(ros_msg.record_event, proto.record_event) - if ros_msg.action_choice == ros_msg.ACTION_AUTO_RETURN_SET: - convert_bosdyn_msgs_action_after_auto_return_to_proto(ros_msg.auto_return, proto.auto_return) - if ros_msg.action_choice == ros_msg.ACTION_CONTROLLED_MOTORS_OFF_SET: - convert_bosdyn_msgs_action_after_controlled_motors_off_to_proto(ros_msg.controlled_motors_off, proto.controlled_motors_off) - if ros_msg.action_choice == ros_msg.ACTION_IMMEDIATE_ROBOT_OFF_SET: - convert_bosdyn_msgs_action_after_immediate_robot_off_to_proto(ros_msg.immediate_robot_off, proto.immediate_robot_off) - if ros_msg.action_choice == ros_msg.ACTION_LEASE_STALE_SET: - convert_bosdyn_msgs_action_after_lease_stale_to_proto(ros_msg.lease_stale, proto.lease_stale) - - -def convert_proto_to_bosdyn_msgs_action_after(proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter", ros_msg: "bosdyn_msgs.msgs.ActionAfter") -> None: - convert_proto_to_bosdyn_msgs_action_after_one_of_action(proto, ros_msg.action) - convert_proto_to_builtin_interfaces_duration(proto.after, ros_msg.after) - ros_msg.after_is_set = proto.HasField("after") - - -def convert_bosdyn_msgs_action_after_to_proto(ros_msg: "bosdyn_msgs.msgs.ActionAfter", proto: "bosdyn.api.keepalive.keepalive_pb2.ActionAfter") -> None: - proto.Clear() - convert_bosdyn_msgs_action_after_one_of_action_to_proto(ros_msg.action, proto) - if ros_msg.after_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.after, proto.after) - - -def convert_proto_to_bosdyn_msgs_modify_policy_request(proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyRequest", ros_msg: "bosdyn_msgs.msgs.ModifyPolicyRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_policy(proto.to_add, ros_msg.to_add) - ros_msg.to_add_is_set = proto.HasField("to_add") - ros_msg.policy_ids_to_remove = [] - for _item in proto.policy_ids_to_remove: - ros_msg.policy_ids_to_remove.append(_item) - - -def convert_bosdyn_msgs_modify_policy_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ModifyPolicyRequest", proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.to_add_is_set: - convert_bosdyn_msgs_policy_to_proto(ros_msg.to_add, proto.to_add) - del proto.policy_ids_to_remove[:] - for _item in ros_msg.policy_ids_to_remove: - proto.policy_ids_to_remove.append(_item) - - -def convert_proto_to_bosdyn_msgs_modify_policy_response_status(proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyResponse.Status", ros_msg: "bosdyn_msgs.msgs.ModifyPolicyResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_modify_policy_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ModifyPolicyResponseStatus", proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_modify_policy_response(proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyResponse", ros_msg: "bosdyn_msgs.msgs.ModifyPolicyResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_live_policy(proto.added_policy, ros_msg.added_policy) - ros_msg.added_policy_is_set = proto.HasField("added_policy") - from bosdyn_msgs.msg import LivePolicy - ros_msg.removed_policies = [] - for _item in proto.removed_policies: - ros_msg.removed_policies.append(LivePolicy()) - convert_proto_to_bosdyn_msgs_live_policy(_item, ros_msg.removed_policies[-1]) - - -def convert_bosdyn_msgs_modify_policy_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ModifyPolicyResponse", proto: "bosdyn.api.keepalive.keepalive_pb2.ModifyPolicyResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.added_policy_is_set: - convert_bosdyn_msgs_live_policy_to_proto(ros_msg.added_policy, proto.added_policy) - del proto.removed_policies[:] - for _item in ros_msg.removed_policies: - convert_bosdyn_msgs_live_policy_to_proto(_item, proto.removed_policies.add()) - - -def convert_proto_to_bosdyn_msgs_check_in_request(proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInRequest", ros_msg: "bosdyn_msgs.msgs.CheckInRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.policy_id = proto.policy_id - - -def convert_bosdyn_msgs_check_in_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CheckInRequest", proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.policy_id = ros_msg.policy_id - - -def convert_proto_to_bosdyn_msgs_check_in_response_status(proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInResponse.Status", ros_msg: "bosdyn_msgs.msgs.CheckInResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_check_in_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CheckInResponseStatus", proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_check_in_response(proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInResponse", ros_msg: "bosdyn_msgs.msgs.CheckInResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_time(proto.last_checkin, ros_msg.last_checkin) - ros_msg.last_checkin_is_set = proto.HasField("last_checkin") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_check_in_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CheckInResponse", proto: "bosdyn.api.keepalive.keepalive_pb2.CheckInResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.last_checkin_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.last_checkin, proto.last_checkin) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_live_policy(proto: "bosdyn.api.keepalive.keepalive_pb2.LivePolicy", ros_msg: "bosdyn_msgs.msgs.LivePolicy") -> None: - ros_msg.policy_id = proto.policy_id - convert_proto_to_bosdyn_msgs_policy(proto.policy, ros_msg.policy) - ros_msg.policy_is_set = proto.HasField("policy") - convert_proto_to_builtin_interfaces_time(proto.last_checkin, ros_msg.last_checkin) - ros_msg.last_checkin_is_set = proto.HasField("last_checkin") - ros_msg.client_name = proto.client_name - - -def convert_bosdyn_msgs_live_policy_to_proto(ros_msg: "bosdyn_msgs.msgs.LivePolicy", proto: "bosdyn.api.keepalive.keepalive_pb2.LivePolicy") -> None: - proto.Clear() - proto.policy_id = ros_msg.policy_id - if ros_msg.policy_is_set: - convert_bosdyn_msgs_policy_to_proto(ros_msg.policy, proto.policy) - if ros_msg.last_checkin_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.last_checkin, proto.last_checkin) - proto.client_name = ros_msg.client_name - - -def convert_proto_to_bosdyn_msgs_lease(proto: "bosdyn.api.lease_pb2.Lease", ros_msg: "bosdyn_msgs.msgs.Lease") -> None: - ros_msg.resource = proto.resource - ros_msg.epoch = proto.epoch - ros_msg.sequence = [] - for _item in proto.sequence: - ros_msg.sequence.append(_item) - ros_msg.client_names = [] - for _item in proto.client_names: - ros_msg.client_names.append(_item) - - -def convert_bosdyn_msgs_lease_to_proto(ros_msg: "bosdyn_msgs.msgs.Lease", proto: "bosdyn.api.lease_pb2.Lease") -> None: - proto.Clear() - proto.resource = ros_msg.resource - proto.epoch = ros_msg.epoch - del proto.sequence[:] - for _item in ros_msg.sequence: - proto.sequence.append(_item) - del proto.client_names[:] - for _item in ros_msg.client_names: - proto.client_names.append(_item) - - -def convert_proto_to_bosdyn_msgs_resource_tree(proto: "bosdyn.api.lease_pb2.ResourceTree", ros_msg: "bosdyn_msgs.msgs.ResourceTree") -> None: - ros_msg.resource = proto.resource - from bosdyn_msgs.msg import SerializedMessage - ros_msg.sub_resources = [] - for _item in proto.sub_resources: - ros_msg.sub_resources.append(SerializedMessage()) - convert_proto_to_serialized_bosdyn_msgs_resource_tree(_item, ros_msg.sub_resources[-1]) - - -def convert_bosdyn_msgs_resource_tree_to_proto(ros_msg: "bosdyn_msgs.msgs.ResourceTree", proto: "bosdyn.api.lease_pb2.ResourceTree") -> None: - proto.Clear() - proto.resource = ros_msg.resource - del proto.sub_resources[:] - for _item in ros_msg.sub_resources: - convert_serialized_bosdyn_msgs_resource_tree_to_proto(_item, proto.sub_resources.add()) - - -def convert_proto_to_bosdyn_msgs_lease_owner(proto: "bosdyn.api.lease_pb2.LeaseOwner", ros_msg: "bosdyn_msgs.msgs.LeaseOwner") -> None: - ros_msg.client_name = proto.client_name - ros_msg.user_name = proto.user_name - - -def convert_bosdyn_msgs_lease_owner_to_proto(ros_msg: "bosdyn_msgs.msgs.LeaseOwner", proto: "bosdyn.api.lease_pb2.LeaseOwner") -> None: - proto.Clear() - proto.client_name = ros_msg.client_name - proto.user_name = ros_msg.user_name - - -def convert_proto_to_bosdyn_msgs_lease_use_result_status(proto: "bosdyn.api.lease_pb2.LeaseUseResult.Status", ros_msg: "bosdyn_msgs.msgs.LeaseUseResultStatus") -> None: - pass - - -def convert_bosdyn_msgs_lease_use_result_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LeaseUseResultStatus", proto: "bosdyn.api.lease_pb2.LeaseUseResult.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_lease_use_result(proto: "bosdyn.api.lease_pb2.LeaseUseResult", ros_msg: "bosdyn_msgs.msgs.LeaseUseResult") -> None: - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_owner(proto.owner, ros_msg.owner) - ros_msg.owner_is_set = proto.HasField("owner") - convert_proto_to_bosdyn_msgs_lease(proto.attempted_lease, ros_msg.attempted_lease) - ros_msg.attempted_lease_is_set = proto.HasField("attempted_lease") - convert_proto_to_bosdyn_msgs_lease(proto.previous_lease, ros_msg.previous_lease) - ros_msg.previous_lease_is_set = proto.HasField("previous_lease") - convert_proto_to_bosdyn_msgs_lease(proto.latest_known_lease, ros_msg.latest_known_lease) - ros_msg.latest_known_lease_is_set = proto.HasField("latest_known_lease") - from bosdyn_msgs.msg import Lease - ros_msg.latest_resources = [] - for _item in proto.latest_resources: - ros_msg.latest_resources.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.latest_resources[-1]) - - -def convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg: "bosdyn_msgs.msgs.LeaseUseResult", proto: "bosdyn.api.lease_pb2.LeaseUseResult") -> None: - proto.Clear() - proto.status = ros_msg.status.value - if ros_msg.owner_is_set: - convert_bosdyn_msgs_lease_owner_to_proto(ros_msg.owner, proto.owner) - if ros_msg.attempted_lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.attempted_lease, proto.attempted_lease) - if ros_msg.previous_lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.previous_lease, proto.previous_lease) - if ros_msg.latest_known_lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.latest_known_lease, proto.latest_known_lease) - del proto.latest_resources[:] - for _item in ros_msg.latest_resources: - convert_bosdyn_msgs_lease_to_proto(_item, proto.latest_resources.add()) - - -def convert_proto_to_bosdyn_msgs_acquire_lease_request(proto: "bosdyn.api.lease_pb2.AcquireLeaseRequest", ros_msg: "bosdyn_msgs.msgs.AcquireLeaseRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.resource = proto.resource - - -def convert_bosdyn_msgs_acquire_lease_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireLeaseRequest", proto: "bosdyn.api.lease_pb2.AcquireLeaseRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.resource = ros_msg.resource - - -def convert_proto_to_bosdyn_msgs_acquire_lease_response_status(proto: "bosdyn.api.lease_pb2.AcquireLeaseResponse.Status", ros_msg: "bosdyn_msgs.msgs.AcquireLeaseResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_acquire_lease_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireLeaseResponseStatus", proto: "bosdyn.api.lease_pb2.AcquireLeaseResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_acquire_lease_response(proto: "bosdyn.api.lease_pb2.AcquireLeaseResponse", ros_msg: "bosdyn_msgs.msgs.AcquireLeaseResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_lease_owner(proto.lease_owner, ros_msg.lease_owner) - ros_msg.lease_owner_is_set = proto.HasField("lease_owner") - - -def convert_bosdyn_msgs_acquire_lease_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AcquireLeaseResponse", proto: "bosdyn.api.lease_pb2.AcquireLeaseResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.lease_owner_is_set: - convert_bosdyn_msgs_lease_owner_to_proto(ros_msg.lease_owner, proto.lease_owner) - - -def convert_proto_to_bosdyn_msgs_take_lease_request(proto: "bosdyn.api.lease_pb2.TakeLeaseRequest", ros_msg: "bosdyn_msgs.msgs.TakeLeaseRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.resource = proto.resource - - -def convert_bosdyn_msgs_take_lease_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TakeLeaseRequest", proto: "bosdyn.api.lease_pb2.TakeLeaseRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.resource = ros_msg.resource - - -def convert_proto_to_bosdyn_msgs_take_lease_response_status(proto: "bosdyn.api.lease_pb2.TakeLeaseResponse.Status", ros_msg: "bosdyn_msgs.msgs.TakeLeaseResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_take_lease_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TakeLeaseResponseStatus", proto: "bosdyn.api.lease_pb2.TakeLeaseResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_take_lease_response(proto: "bosdyn.api.lease_pb2.TakeLeaseResponse", ros_msg: "bosdyn_msgs.msgs.TakeLeaseResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_lease_owner(proto.lease_owner, ros_msg.lease_owner) - ros_msg.lease_owner_is_set = proto.HasField("lease_owner") - - -def convert_bosdyn_msgs_take_lease_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TakeLeaseResponse", proto: "bosdyn.api.lease_pb2.TakeLeaseResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.lease_owner_is_set: - convert_bosdyn_msgs_lease_owner_to_proto(ros_msg.lease_owner, proto.lease_owner) - - -def convert_proto_to_bosdyn_msgs_return_lease_request(proto: "bosdyn.api.lease_pb2.ReturnLeaseRequest", ros_msg: "bosdyn_msgs.msgs.ReturnLeaseRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_return_lease_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ReturnLeaseRequest", proto: "bosdyn.api.lease_pb2.ReturnLeaseRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_return_lease_response_status(proto: "bosdyn.api.lease_pb2.ReturnLeaseResponse.Status", ros_msg: "bosdyn_msgs.msgs.ReturnLeaseResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_return_lease_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ReturnLeaseResponseStatus", proto: "bosdyn.api.lease_pb2.ReturnLeaseResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_return_lease_response(proto: "bosdyn.api.lease_pb2.ReturnLeaseResponse", ros_msg: "bosdyn_msgs.msgs.ReturnLeaseResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_return_lease_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ReturnLeaseResponse", proto: "bosdyn.api.lease_pb2.ReturnLeaseResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_list_leases_request(proto: "bosdyn.api.lease_pb2.ListLeasesRequest", ros_msg: "bosdyn_msgs.msgs.ListLeasesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.include_full_lease_info = proto.include_full_lease_info - - -def convert_bosdyn_msgs_list_leases_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListLeasesRequest", proto: "bosdyn.api.lease_pb2.ListLeasesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.include_full_lease_info = ros_msg.include_full_lease_info - - -def convert_proto_to_bosdyn_msgs_lease_resource(proto: "bosdyn.api.lease_pb2.LeaseResource", ros_msg: "bosdyn_msgs.msgs.LeaseResource") -> None: - ros_msg.resource = proto.resource - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_lease_owner(proto.lease_owner, ros_msg.lease_owner) - ros_msg.lease_owner_is_set = proto.HasField("lease_owner") - ros_msg.is_stale = proto.is_stale - - -def convert_bosdyn_msgs_lease_resource_to_proto(ros_msg: "bosdyn_msgs.msgs.LeaseResource", proto: "bosdyn.api.lease_pb2.LeaseResource") -> None: - proto.Clear() - proto.resource = ros_msg.resource - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.lease_owner_is_set: - convert_bosdyn_msgs_lease_owner_to_proto(ros_msg.lease_owner, proto.lease_owner) - proto.is_stale = ros_msg.is_stale - - -def convert_proto_to_bosdyn_msgs_list_leases_response(proto: "bosdyn.api.lease_pb2.ListLeasesResponse", ros_msg: "bosdyn_msgs.msgs.ListLeasesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LeaseResource - ros_msg.resources = [] - for _item in proto.resources: - ros_msg.resources.append(LeaseResource()) - convert_proto_to_bosdyn_msgs_lease_resource(_item, ros_msg.resources[-1]) - convert_proto_to_bosdyn_msgs_resource_tree(proto.resource_tree, ros_msg.resource_tree) - ros_msg.resource_tree_is_set = proto.HasField("resource_tree") - - -def convert_bosdyn_msgs_list_leases_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListLeasesResponse", proto: "bosdyn.api.lease_pb2.ListLeasesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.resources[:] - for _item in ros_msg.resources: - convert_bosdyn_msgs_lease_resource_to_proto(_item, proto.resources.add()) - if ros_msg.resource_tree_is_set: - convert_bosdyn_msgs_resource_tree_to_proto(ros_msg.resource_tree, proto.resource_tree) - - -def convert_proto_to_bosdyn_msgs_retain_lease_request(proto: "bosdyn.api.lease_pb2.RetainLeaseRequest", ros_msg: "bosdyn_msgs.msgs.RetainLeaseRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_retain_lease_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RetainLeaseRequest", proto: "bosdyn.api.lease_pb2.RetainLeaseRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_retain_lease_response(proto: "bosdyn.api.lease_pb2.RetainLeaseResponse", ros_msg: "bosdyn_msgs.msgs.RetainLeaseResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_retain_lease_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RetainLeaseResponse", proto: "bosdyn.api.lease_pb2.RetainLeaseResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_license_info_status(proto: "bosdyn.api.license_pb2.LicenseInfo.Status", ros_msg: "bosdyn_msgs.msgs.LicenseInfoStatus") -> None: - pass - - -def convert_bosdyn_msgs_license_info_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LicenseInfoStatus", proto: "bosdyn.api.license_pb2.LicenseInfo.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_license_info(proto: "bosdyn.api.license_pb2.LicenseInfo", ros_msg: "bosdyn_msgs.msgs.LicenseInfo") -> None: - ros_msg.status.value = proto.status - ros_msg.id = proto.id - ros_msg.robot_serial = proto.robot_serial - convert_proto_to_builtin_interfaces_time(proto.not_valid_before, ros_msg.not_valid_before) - ros_msg.not_valid_before_is_set = proto.HasField("not_valid_before") - convert_proto_to_builtin_interfaces_time(proto.not_valid_after, ros_msg.not_valid_after) - ros_msg.not_valid_after_is_set = proto.HasField("not_valid_after") - ros_msg.licensed_features = [] - for _item in proto.licensed_features: - ros_msg.licensed_features.append(_item) - - -def convert_bosdyn_msgs_license_info_to_proto(ros_msg: "bosdyn_msgs.msgs.LicenseInfo", proto: "bosdyn.api.license_pb2.LicenseInfo") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.id = ros_msg.id - proto.robot_serial = ros_msg.robot_serial - if ros_msg.not_valid_before_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.not_valid_before, proto.not_valid_before) - if ros_msg.not_valid_after_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.not_valid_after, proto.not_valid_after) - del proto.licensed_features[:] - for _item in ros_msg.licensed_features: - proto.licensed_features.append(_item) - - -def convert_proto_to_bosdyn_msgs_get_license_info_request(proto: "bosdyn.api.license_pb2.GetLicenseInfoRequest", ros_msg: "bosdyn_msgs.msgs.GetLicenseInfoRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_license_info_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLicenseInfoRequest", proto: "bosdyn.api.license_pb2.GetLicenseInfoRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_license_info_response(proto: "bosdyn.api.license_pb2.GetLicenseInfoResponse", ros_msg: "bosdyn_msgs.msgs.GetLicenseInfoResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_license_info(proto.license, ros_msg.license) - ros_msg.license_is_set = proto.HasField("license") - - -def convert_bosdyn_msgs_get_license_info_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLicenseInfoResponse", proto: "bosdyn.api.license_pb2.GetLicenseInfoResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.license_is_set: - convert_bosdyn_msgs_license_info_to_proto(ros_msg.license, proto.license) - - -def convert_proto_to_bosdyn_msgs_get_feature_enabled_request(proto: "bosdyn.api.license_pb2.GetFeatureEnabledRequest", ros_msg: "bosdyn_msgs.msgs.GetFeatureEnabledRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.feature_codes = [] - for _item in proto.feature_codes: - ros_msg.feature_codes.append(_item) - - -def convert_bosdyn_msgs_get_feature_enabled_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetFeatureEnabledRequest", proto: "bosdyn.api.license_pb2.GetFeatureEnabledRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.feature_codes[:] - for _item in ros_msg.feature_codes: - proto.feature_codes.append(_item) - - -def convert_proto_to_bosdyn_msgs_get_feature_enabled_response(proto: "bosdyn.api.license_pb2.GetFeatureEnabledResponse", ros_msg: "bosdyn_msgs.msgs.GetFeatureEnabledResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import KeyStringValueBool - ros_msg.feature_enabled = [] - for _item in proto.feature_enabled: - ros_msg.feature_enabled.append(KeyStringValueBool()) - ros_msg.feature_enabled[-1].key = _item - ros_msg.feature_enabled[-1].value = proto.feature_enabled[_item] - - -def convert_bosdyn_msgs_get_feature_enabled_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetFeatureEnabledResponse", proto: "bosdyn.api.license_pb2.GetFeatureEnabledResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - for _item in ros_msg.feature_enabled: - proto.feature_enabled[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_local_grid_type(proto: "bosdyn.api.local_grid_pb2.LocalGridType", ros_msg: "bosdyn_msgs.msgs.LocalGridType") -> None: - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_local_grid_type_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridType", proto: "bosdyn.api.local_grid_pb2.LocalGridType") -> None: - proto.Clear() - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_local_grid_request(proto: "bosdyn.api.local_grid_pb2.LocalGridRequest", ros_msg: "bosdyn_msgs.msgs.LocalGridRequest") -> None: - ros_msg.local_grid_type_name = proto.local_grid_type_name - - -def convert_bosdyn_msgs_local_grid_request_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridRequest", proto: "bosdyn.api.local_grid_pb2.LocalGridRequest") -> None: - proto.Clear() - proto.local_grid_type_name = ros_msg.local_grid_type_name - - -def convert_proto_to_bosdyn_msgs_local_grid_extent(proto: "bosdyn.api.local_grid_pb2.LocalGridExtent", ros_msg: "bosdyn_msgs.msgs.LocalGridExtent") -> None: - ros_msg.cell_size = proto.cell_size - ros_msg.num_cells_x = proto.num_cells_x - ros_msg.num_cells_y = proto.num_cells_y - - -def convert_bosdyn_msgs_local_grid_extent_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridExtent", proto: "bosdyn.api.local_grid_pb2.LocalGridExtent") -> None: - proto.Clear() - proto.cell_size = ros_msg.cell_size - proto.num_cells_x = ros_msg.num_cells_x - proto.num_cells_y = ros_msg.num_cells_y - - -def convert_proto_to_bosdyn_msgs_local_grid_cell_format(proto: "bosdyn.api.local_grid_pb2.LocalGrid.CellFormat", ros_msg: "bosdyn_msgs.msgs.LocalGridCellFormat") -> None: - pass - - -def convert_bosdyn_msgs_local_grid_cell_format_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridCellFormat", proto: "bosdyn.api.local_grid_pb2.LocalGrid.CellFormat") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_local_grid_encoding(proto: "bosdyn.api.local_grid_pb2.LocalGrid.Encoding", ros_msg: "bosdyn_msgs.msgs.LocalGridEncoding") -> None: - pass - - -def convert_bosdyn_msgs_local_grid_encoding_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridEncoding", proto: "bosdyn.api.local_grid_pb2.LocalGrid.Encoding") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_local_grid(proto: "bosdyn.api.local_grid_pb2.LocalGrid", ros_msg: "bosdyn_msgs.msgs.LocalGrid") -> None: - ros_msg.local_grid_type_name = proto.local_grid_type_name - convert_proto_to_builtin_interfaces_time(proto.acquisition_time, ros_msg.acquisition_time) - ros_msg.acquisition_time_is_set = proto.HasField("acquisition_time") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - ros_msg.frame_name_local_grid_data = proto.frame_name_local_grid_data - convert_proto_to_bosdyn_msgs_local_grid_extent(proto.extent, ros_msg.extent) - ros_msg.extent_is_set = proto.HasField("extent") - ros_msg.cell_format.value = proto.cell_format - ros_msg.encoding.value = proto.encoding - ros_msg.data = proto.data - ros_msg.rle_counts = [] - for _item in proto.rle_counts: - ros_msg.rle_counts.append(_item) - ros_msg.cell_value_scale = proto.cell_value_scale - ros_msg.cell_value_offset = proto.cell_value_offset - - -def convert_bosdyn_msgs_local_grid_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGrid", proto: "bosdyn.api.local_grid_pb2.LocalGrid") -> None: - proto.Clear() - proto.local_grid_type_name = ros_msg.local_grid_type_name - if ros_msg.acquisition_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.acquisition_time, proto.acquisition_time) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - proto.frame_name_local_grid_data = ros_msg.frame_name_local_grid_data - if ros_msg.extent_is_set: - convert_bosdyn_msgs_local_grid_extent_to_proto(ros_msg.extent, proto.extent) - proto.cell_format = ros_msg.cell_format.value - proto.encoding = ros_msg.encoding.value - proto.data = ros_msg.data - del proto.rle_counts[:] - for _item in ros_msg.rle_counts: - proto.rle_counts.append(_item) - proto.cell_value_scale = ros_msg.cell_value_scale - proto.cell_value_offset = ros_msg.cell_value_offset - - -def convert_proto_to_bosdyn_msgs_local_grid_response_status(proto: "bosdyn.api.local_grid_pb2.LocalGridResponse.Status", ros_msg: "bosdyn_msgs.msgs.LocalGridResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_local_grid_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridResponseStatus", proto: "bosdyn.api.local_grid_pb2.LocalGridResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_local_grid_response(proto: "bosdyn.api.local_grid_pb2.LocalGridResponse", ros_msg: "bosdyn_msgs.msgs.LocalGridResponse") -> None: - ros_msg.local_grid_type_name = proto.local_grid_type_name - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_local_grid(proto.local_grid, ros_msg.local_grid) - ros_msg.local_grid_is_set = proto.HasField("local_grid") - - -def convert_bosdyn_msgs_local_grid_response_to_proto(ros_msg: "bosdyn_msgs.msgs.LocalGridResponse", proto: "bosdyn.api.local_grid_pb2.LocalGridResponse") -> None: - proto.Clear() - proto.local_grid_type_name = ros_msg.local_grid_type_name - proto.status = ros_msg.status.value - if ros_msg.local_grid_is_set: - convert_bosdyn_msgs_local_grid_to_proto(ros_msg.local_grid, proto.local_grid) - - -def convert_proto_to_bosdyn_msgs_get_local_grid_types_request(proto: "bosdyn.api.local_grid_pb2.GetLocalGridTypesRequest", ros_msg: "bosdyn_msgs.msgs.GetLocalGridTypesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_local_grid_types_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalGridTypesRequest", proto: "bosdyn.api.local_grid_pb2.GetLocalGridTypesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_local_grid_types_response(proto: "bosdyn.api.local_grid_pb2.GetLocalGridTypesResponse", ros_msg: "bosdyn_msgs.msgs.GetLocalGridTypesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LocalGridType - ros_msg.local_grid_type = [] - for _item in proto.local_grid_type: - ros_msg.local_grid_type.append(LocalGridType()) - convert_proto_to_bosdyn_msgs_local_grid_type(_item, ros_msg.local_grid_type[-1]) - - -def convert_bosdyn_msgs_get_local_grid_types_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalGridTypesResponse", proto: "bosdyn.api.local_grid_pb2.GetLocalGridTypesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.local_grid_type[:] - for _item in ros_msg.local_grid_type: - convert_bosdyn_msgs_local_grid_type_to_proto(_item, proto.local_grid_type.add()) - - -def convert_proto_to_bosdyn_msgs_get_local_grids_request(proto: "bosdyn.api.local_grid_pb2.GetLocalGridsRequest", ros_msg: "bosdyn_msgs.msgs.GetLocalGridsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LocalGridRequest - ros_msg.local_grid_requests = [] - for _item in proto.local_grid_requests: - ros_msg.local_grid_requests.append(LocalGridRequest()) - convert_proto_to_bosdyn_msgs_local_grid_request(_item, ros_msg.local_grid_requests[-1]) - - -def convert_bosdyn_msgs_get_local_grids_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalGridsRequest", proto: "bosdyn.api.local_grid_pb2.GetLocalGridsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.local_grid_requests[:] - for _item in ros_msg.local_grid_requests: - convert_bosdyn_msgs_local_grid_request_to_proto(_item, proto.local_grid_requests.add()) - - -def convert_proto_to_bosdyn_msgs_get_local_grids_response(proto: "bosdyn.api.local_grid_pb2.GetLocalGridsResponse", ros_msg: "bosdyn_msgs.msgs.GetLocalGridsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import LocalGridResponse - ros_msg.local_grid_responses = [] - for _item in proto.local_grid_responses: - ros_msg.local_grid_responses.append(LocalGridResponse()) - convert_proto_to_bosdyn_msgs_local_grid_response(_item, ros_msg.local_grid_responses[-1]) - ros_msg.num_local_grid_errors = proto.num_local_grid_errors - - -def convert_bosdyn_msgs_get_local_grids_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLocalGridsResponse", proto: "bosdyn.api.local_grid_pb2.GetLocalGridsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.local_grid_responses[:] - for _item in ros_msg.local_grid_responses: - convert_bosdyn_msgs_local_grid_response_to_proto(_item, proto.local_grid_responses.add()) - proto.num_local_grid_errors = ros_msg.num_local_grid_errors - - -def convert_proto_to_bosdyn_msgs_add_log_annotation_request(proto: "bosdyn.api.log_annotation_pb2.AddLogAnnotationRequest", ros_msg: "bosdyn_msgs.msgs.AddLogAnnotationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_log_annotations(proto.annotations, ros_msg.annotations) - ros_msg.annotations_is_set = proto.HasField("annotations") - - -def convert_bosdyn_msgs_add_log_annotation_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AddLogAnnotationRequest", proto: "bosdyn.api.log_annotation_pb2.AddLogAnnotationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.annotations_is_set: - convert_bosdyn_msgs_log_annotations_to_proto(ros_msg.annotations, proto.annotations) - - -def convert_proto_to_bosdyn_msgs_log_annotations(proto: "bosdyn.api.log_annotation_pb2.LogAnnotations", ros_msg: "bosdyn_msgs.msgs.LogAnnotations") -> None: - from bosdyn_msgs.msg import LogAnnotationTextMessage - ros_msg.text_messages = [] - for _item in proto.text_messages: - ros_msg.text_messages.append(LogAnnotationTextMessage()) - convert_proto_to_bosdyn_msgs_log_annotation_text_message(_item, ros_msg.text_messages[-1]) - from bosdyn_msgs.msg import LogAnnotationOperatorMessage - ros_msg.operator_messages = [] - for _item in proto.operator_messages: - ros_msg.operator_messages.append(LogAnnotationOperatorMessage()) - convert_proto_to_bosdyn_msgs_log_annotation_operator_message(_item, ros_msg.operator_messages[-1]) - from bosdyn_msgs.msg import LogAnnotationLogBlob - ros_msg.blob_data = [] - for _item in proto.blob_data: - ros_msg.blob_data.append(LogAnnotationLogBlob()) - convert_proto_to_bosdyn_msgs_log_annotation_log_blob(_item, ros_msg.blob_data[-1]) - - -def convert_bosdyn_msgs_log_annotations_to_proto(ros_msg: "bosdyn_msgs.msgs.LogAnnotations", proto: "bosdyn.api.log_annotation_pb2.LogAnnotations") -> None: - proto.Clear() - del proto.text_messages[:] - for _item in ros_msg.text_messages: - convert_bosdyn_msgs_log_annotation_text_message_to_proto(_item, proto.text_messages.add()) - del proto.operator_messages[:] - for _item in ros_msg.operator_messages: - convert_bosdyn_msgs_log_annotation_operator_message_to_proto(_item, proto.operator_messages.add()) - del proto.blob_data[:] - for _item in ros_msg.blob_data: - convert_bosdyn_msgs_log_annotation_log_blob_to_proto(_item, proto.blob_data.add()) - - -def convert_proto_to_bosdyn_msgs_log_annotation_text_message_level(proto: "bosdyn.api.log_annotation_pb2.LogAnnotationTextMessage.Level", ros_msg: "bosdyn_msgs.msgs.LogAnnotationTextMessageLevel") -> None: - pass - - -def convert_bosdyn_msgs_log_annotation_text_message_level_to_proto(ros_msg: "bosdyn_msgs.msgs.LogAnnotationTextMessageLevel", proto: "bosdyn.api.log_annotation_pb2.LogAnnotationTextMessage.Level") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_log_annotation_text_message(proto: "bosdyn.api.log_annotation_pb2.LogAnnotationTextMessage", ros_msg: "bosdyn_msgs.msgs.LogAnnotationTextMessage") -> None: - ros_msg.message = proto.message - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.service = proto.service - ros_msg.level.value = proto.level - ros_msg.tag = proto.tag - ros_msg.filename = proto.filename - ros_msg.line_number = proto.line_number - convert_proto_to_builtin_interfaces_time(proto.timestamp_client, ros_msg.timestamp_client) - ros_msg.timestamp_client_is_set = proto.HasField("timestamp_client") - - -def convert_bosdyn_msgs_log_annotation_text_message_to_proto(ros_msg: "bosdyn_msgs.msgs.LogAnnotationTextMessage", proto: "bosdyn.api.log_annotation_pb2.LogAnnotationTextMessage") -> None: - proto.Clear() - proto.message = ros_msg.message - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.service = ros_msg.service - proto.level = ros_msg.level.value - proto.tag = ros_msg.tag - proto.filename = ros_msg.filename - proto.line_number = ros_msg.line_number - if ros_msg.timestamp_client_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp_client, proto.timestamp_client) - - -def convert_proto_to_bosdyn_msgs_log_annotation_operator_message(proto: "bosdyn.api.log_annotation_pb2.LogAnnotationOperatorMessage", ros_msg: "bosdyn_msgs.msgs.LogAnnotationOperatorMessage") -> None: - ros_msg.message = proto.message - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - convert_proto_to_builtin_interfaces_time(proto.timestamp_client, ros_msg.timestamp_client) - ros_msg.timestamp_client_is_set = proto.HasField("timestamp_client") - - -def convert_bosdyn_msgs_log_annotation_operator_message_to_proto(ros_msg: "bosdyn_msgs.msgs.LogAnnotationOperatorMessage", proto: "bosdyn.api.log_annotation_pb2.LogAnnotationOperatorMessage") -> None: - proto.Clear() - proto.message = ros_msg.message - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - if ros_msg.timestamp_client_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp_client, proto.timestamp_client) - - -def convert_proto_to_bosdyn_msgs_log_annotation_log_blob(proto: "bosdyn.api.log_annotation_pb2.LogAnnotationLogBlob", ros_msg: "bosdyn_msgs.msgs.LogAnnotationLogBlob") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.channel = proto.channel - ros_msg.type_id = proto.type_id - ros_msg.data = proto.data - convert_proto_to_builtin_interfaces_time(proto.timestamp_client, ros_msg.timestamp_client) - ros_msg.timestamp_client_is_set = proto.HasField("timestamp_client") - - -def convert_bosdyn_msgs_log_annotation_log_blob_to_proto(ros_msg: "bosdyn_msgs.msgs.LogAnnotationLogBlob", proto: "bosdyn.api.log_annotation_pb2.LogAnnotationLogBlob") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.channel = ros_msg.channel - proto.type_id = ros_msg.type_id - proto.data = ros_msg.data - if ros_msg.timestamp_client_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp_client, proto.timestamp_client) - - -def convert_proto_to_bosdyn_msgs_add_log_annotation_response(proto: "bosdyn.api.log_annotation_pb2.AddLogAnnotationResponse", ros_msg: "bosdyn_msgs.msgs.AddLogAnnotationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_add_log_annotation_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AddLogAnnotationResponse", proto: "bosdyn.api.log_annotation_pb2.AddLogAnnotationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_log_status_status(proto: "bosdyn.api.log_status.log_status_pb2.LogStatus.Status", ros_msg: "bosdyn_msgs.msgs.LogStatusStatus") -> None: - pass - - -def convert_bosdyn_msgs_log_status_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LogStatusStatus", proto: "bosdyn.api.log_status.log_status_pb2.LogStatus.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_log_status_type(proto: "bosdyn.api.log_status.log_status_pb2.LogStatus.Type", ros_msg: "bosdyn_msgs.msgs.LogStatusType") -> None: - pass - - -def convert_bosdyn_msgs_log_status_type_to_proto(ros_msg: "bosdyn_msgs.msgs.LogStatusType", proto: "bosdyn.api.log_status.log_status_pb2.LogStatus.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_log_status(proto: "bosdyn.api.log_status.log_status_pb2.LogStatus", ros_msg: "bosdyn_msgs.msgs.LogStatus") -> None: - ros_msg.id = proto.id - ros_msg.status.value = proto.status - ros_msg.type.value = proto.type - - -def convert_bosdyn_msgs_log_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LogStatus", proto: "bosdyn.api.log_status.log_status_pb2.LogStatus") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.status = ros_msg.status.value - proto.type = ros_msg.type.value - - -def convert_proto_to_bosdyn_msgs_get_log_status_request(proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetLogStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_get_log_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLogStatusRequest", proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_get_log_status_response_status(proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetLogStatusResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_log_status_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLogStatusResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_log_status_response(proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetLogStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_log_status(proto.log_status, ros_msg.log_status) - ros_msg.log_status_is_set = proto.HasField("log_status") - - -def convert_bosdyn_msgs_get_log_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLogStatusResponse", proto: "bosdyn.api.log_status.log_status_pb2.GetLogStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.log_status_is_set: - convert_bosdyn_msgs_log_status_to_proto(ros_msg.log_status, proto.log_status) - - -def convert_proto_to_bosdyn_msgs_get_active_log_statuses_request(proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesRequest", ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_active_log_statuses_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesRequest", proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_active_log_statuses_response_status(proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_active_log_statuses_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_active_log_statuses_response(proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesResponse", ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import LogStatus - ros_msg.log_statuses = [] - for _item in proto.log_statuses: - ros_msg.log_statuses.append(LogStatus()) - convert_proto_to_bosdyn_msgs_log_status(_item, ros_msg.log_statuses[-1]) - - -def convert_bosdyn_msgs_get_active_log_statuses_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetActiveLogStatusesResponse", proto: "bosdyn.api.log_status.log_status_pb2.GetActiveLogStatusesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.log_statuses[:] - for _item in ros_msg.log_statuses: - convert_bosdyn_msgs_log_status_to_proto(_item, proto.log_statuses.add()) - - -def convert_proto_to_bosdyn_msgs_start_retro_log_request(proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogRequest", ros_msg: "bosdyn_msgs.msgs.StartRetroLogRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_duration(proto.past_duration, ros_msg.past_duration) - ros_msg.past_duration_is_set = proto.HasField("past_duration") - - -def convert_bosdyn_msgs_start_retro_log_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRetroLogRequest", proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.past_duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.past_duration, proto.past_duration) - - -def convert_proto_to_bosdyn_msgs_start_retro_log_response_status(proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogResponse.Status", ros_msg: "bosdyn_msgs.msgs.StartRetroLogResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_start_retro_log_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRetroLogResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_start_retro_log_response(proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogResponse", ros_msg: "bosdyn_msgs.msgs.StartRetroLogResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_log_status(proto.log_status, ros_msg.log_status) - ros_msg.log_status_is_set = proto.HasField("log_status") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - - -def convert_bosdyn_msgs_start_retro_log_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StartRetroLogResponse", proto: "bosdyn.api.log_status.log_status_pb2.StartRetroLogResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.log_status_is_set: - convert_bosdyn_msgs_log_status_to_proto(ros_msg.log_status, proto.log_status) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - - -def convert_proto_to_bosdyn_msgs_start_experiment_log_request(proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogRequest", ros_msg: "bosdyn_msgs.msgs.StartExperimentLogRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_duration(proto.keep_alive, ros_msg.keep_alive) - ros_msg.keep_alive_is_set = proto.HasField("keep_alive") - - -def convert_bosdyn_msgs_start_experiment_log_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StartExperimentLogRequest", proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.keep_alive_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.keep_alive, proto.keep_alive) - - -def convert_proto_to_bosdyn_msgs_start_experiment_log_response_status(proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogResponse.Status", ros_msg: "bosdyn_msgs.msgs.StartExperimentLogResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_start_experiment_log_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StartExperimentLogResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_start_experiment_log_response(proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogResponse", ros_msg: "bosdyn_msgs.msgs.StartExperimentLogResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_log_status(proto.log_status, ros_msg.log_status) - ros_msg.log_status_is_set = proto.HasField("log_status") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - - -def convert_bosdyn_msgs_start_experiment_log_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StartExperimentLogResponse", proto: "bosdyn.api.log_status.log_status_pb2.StartExperimentLogResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.log_status_is_set: - convert_bosdyn_msgs_log_status_to_proto(ros_msg.log_status, proto.log_status) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - - -def convert_proto_to_bosdyn_msgs_update_experiment_log_request(proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogRequest", ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_duration(proto.keep_alive, ros_msg.keep_alive) - ros_msg.keep_alive_is_set = proto.HasField("keep_alive") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_update_experiment_log_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogRequest", proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.keep_alive_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.keep_alive, proto.keep_alive) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_update_experiment_log_response_status(proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogResponse.Status", ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_update_experiment_log_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_experiment_log_response(proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogResponse", ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_log_status(proto.log_status, ros_msg.log_status) - ros_msg.log_status_is_set = proto.HasField("log_status") - convert_proto_to_builtin_interfaces_time(proto.end_time, ros_msg.end_time) - ros_msg.end_time_is_set = proto.HasField("end_time") - - -def convert_bosdyn_msgs_update_experiment_log_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdateExperimentLogResponse", proto: "bosdyn.api.log_status.log_status_pb2.UpdateExperimentLogResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.log_status_is_set: - convert_bosdyn_msgs_log_status_to_proto(ros_msg.log_status, proto.log_status) - if ros_msg.end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end_time, proto.end_time) - - -def convert_proto_to_bosdyn_msgs_terminate_log_request(proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogRequest", ros_msg: "bosdyn_msgs.msgs.TerminateLogRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_terminate_log_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TerminateLogRequest", proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_terminate_log_response_status(proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogResponse.Status", ros_msg: "bosdyn_msgs.msgs.TerminateLogResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_terminate_log_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TerminateLogResponseStatus", proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_terminate_log_response(proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogResponse", ros_msg: "bosdyn_msgs.msgs.TerminateLogResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_log_status(proto.log_status, ros_msg.log_status) - ros_msg.log_status_is_set = proto.HasField("log_status") - - -def convert_bosdyn_msgs_terminate_log_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TerminateLogResponse", proto: "bosdyn.api.log_status.log_status_pb2.TerminateLogResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.log_status_is_set: - convert_bosdyn_msgs_log_status_to_proto(ros_msg.log_status, proto.log_status) - - -def convert_proto_to_bosdyn_msgs_walk_to_object_ray_in_world(proto: "bosdyn.api.manipulation_api_pb2.WalkToObjectRayInWorld", ros_msg: "bosdyn_msgs.msgs.WalkToObjectRayInWorld") -> None: - convert_proto_to_geometry_msgs_vector3(proto.ray_start_rt_frame, ros_msg.ray_start_rt_frame) - ros_msg.ray_start_rt_frame_is_set = proto.HasField("ray_start_rt_frame") - convert_proto_to_geometry_msgs_vector3(proto.ray_end_rt_frame, ros_msg.ray_end_rt_frame) - ros_msg.ray_end_rt_frame_is_set = proto.HasField("ray_end_rt_frame") - ros_msg.frame_name = proto.frame_name - ros_msg.offset_distance = proto.offset_distance.value - ros_msg.offset_distance_is_set = proto.HasField("offset_distance") - - -def convert_bosdyn_msgs_walk_to_object_ray_in_world_to_proto(ros_msg: "bosdyn_msgs.msgs.WalkToObjectRayInWorld", proto: "bosdyn.api.manipulation_api_pb2.WalkToObjectRayInWorld") -> None: - proto.Clear() - if ros_msg.ray_start_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ray_start_rt_frame, proto.ray_start_rt_frame) - if ros_msg.ray_end_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ray_end_rt_frame, proto.ray_end_rt_frame) - proto.frame_name = ros_msg.frame_name - if ros_msg.offset_distance_is_set: - convert_float32_to_proto(ros_msg.offset_distance, proto.offset_distance) - - -def convert_proto_to_bosdyn_msgs_walk_to_object_in_image(proto: "bosdyn.api.manipulation_api_pb2.WalkToObjectInImage", ros_msg: "bosdyn_msgs.msgs.WalkToObjectInImage") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.pixel_xy, ros_msg.pixel_xy) - ros_msg.pixel_xy_is_set = proto.HasField("pixel_xy") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot_for_camera, ros_msg.transforms_snapshot_for_camera) - ros_msg.transforms_snapshot_for_camera_is_set = proto.HasField("transforms_snapshot_for_camera") - ros_msg.frame_name_image_sensor = proto.frame_name_image_sensor - convert_proto_to_bosdyn_msgs_image_source_pinhole_model(proto.camera_model, ros_msg.camera_model) - ros_msg.camera_model_is_set = proto.HasField("camera_model") - ros_msg.offset_distance = proto.offset_distance.value - ros_msg.offset_distance_is_set = proto.HasField("offset_distance") - - -def convert_bosdyn_msgs_walk_to_object_in_image_to_proto(ros_msg: "bosdyn_msgs.msgs.WalkToObjectInImage", proto: "bosdyn.api.manipulation_api_pb2.WalkToObjectInImage") -> None: - proto.Clear() - if ros_msg.pixel_xy_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.pixel_xy, proto.pixel_xy) - if ros_msg.transforms_snapshot_for_camera_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot_for_camera, proto.transforms_snapshot_for_camera) - proto.frame_name_image_sensor = ros_msg.frame_name_image_sensor - if ros_msg.camera_model_is_set: - convert_bosdyn_msgs_image_source_pinhole_model_to_proto(ros_msg.camera_model, proto.camera_model) - if ros_msg.offset_distance_is_set: - convert_float32_to_proto(ros_msg.offset_distance, proto.offset_distance) - - -def convert_proto_to_bosdyn_msgs_pick_object_ray_in_world(proto: "bosdyn.api.manipulation_api_pb2.PickObjectRayInWorld", ros_msg: "bosdyn_msgs.msgs.PickObjectRayInWorld") -> None: - convert_proto_to_geometry_msgs_vector3(proto.ray_start_rt_frame, ros_msg.ray_start_rt_frame) - ros_msg.ray_start_rt_frame_is_set = proto.HasField("ray_start_rt_frame") - convert_proto_to_geometry_msgs_vector3(proto.ray_end_rt_frame, ros_msg.ray_end_rt_frame) - ros_msg.ray_end_rt_frame_is_set = proto.HasField("ray_end_rt_frame") - ros_msg.frame_name = proto.frame_name - convert_proto_to_bosdyn_msgs_grasp_params(proto.grasp_params, ros_msg.grasp_params) - ros_msg.grasp_params_is_set = proto.HasField("grasp_params") - ros_msg.walk_gaze_mode.value = proto.walk_gaze_mode - - -def convert_bosdyn_msgs_pick_object_ray_in_world_to_proto(ros_msg: "bosdyn_msgs.msgs.PickObjectRayInWorld", proto: "bosdyn.api.manipulation_api_pb2.PickObjectRayInWorld") -> None: - proto.Clear() - if ros_msg.ray_start_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ray_start_rt_frame, proto.ray_start_rt_frame) - if ros_msg.ray_end_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ray_end_rt_frame, proto.ray_end_rt_frame) - proto.frame_name = ros_msg.frame_name - if ros_msg.grasp_params_is_set: - convert_bosdyn_msgs_grasp_params_to_proto(ros_msg.grasp_params, proto.grasp_params) - proto.walk_gaze_mode = ros_msg.walk_gaze_mode.value - - -def convert_proto_to_bosdyn_msgs_pick_object_execute_plan(proto: "bosdyn.api.manipulation_api_pb2.PickObjectExecutePlan", ros_msg: "bosdyn_msgs.msgs.PickObjectExecutePlan") -> None: - pass - - -def convert_bosdyn_msgs_pick_object_execute_plan_to_proto(ros_msg: "bosdyn_msgs.msgs.PickObjectExecutePlan", proto: "bosdyn.api.manipulation_api_pb2.PickObjectExecutePlan") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_pick_object(proto: "bosdyn.api.manipulation_api_pb2.PickObject", ros_msg: "bosdyn_msgs.msgs.PickObject") -> None: - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.object_rt_frame, ros_msg.object_rt_frame) - ros_msg.object_rt_frame_is_set = proto.HasField("object_rt_frame") - convert_proto_to_bosdyn_msgs_grasp_params(proto.grasp_params, ros_msg.grasp_params) - ros_msg.grasp_params_is_set = proto.HasField("grasp_params") - - -def convert_bosdyn_msgs_pick_object_to_proto(ros_msg: "bosdyn_msgs.msgs.PickObject", proto: "bosdyn.api.manipulation_api_pb2.PickObject") -> None: - proto.Clear() - proto.frame_name = ros_msg.frame_name - if ros_msg.object_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.object_rt_frame, proto.object_rt_frame) - if ros_msg.grasp_params_is_set: - convert_bosdyn_msgs_grasp_params_to_proto(ros_msg.grasp_params, proto.grasp_params) - - -def convert_proto_to_bosdyn_msgs_pick_object_in_image(proto: "bosdyn.api.manipulation_api_pb2.PickObjectInImage", ros_msg: "bosdyn_msgs.msgs.PickObjectInImage") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.pixel_xy, ros_msg.pixel_xy) - ros_msg.pixel_xy_is_set = proto.HasField("pixel_xy") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot_for_camera, ros_msg.transforms_snapshot_for_camera) - ros_msg.transforms_snapshot_for_camera_is_set = proto.HasField("transforms_snapshot_for_camera") - ros_msg.frame_name_image_sensor = proto.frame_name_image_sensor - convert_proto_to_bosdyn_msgs_image_source_pinhole_model(proto.camera_model, ros_msg.camera_model) - ros_msg.camera_model_is_set = proto.HasField("camera_model") - convert_proto_to_bosdyn_msgs_grasp_params(proto.grasp_params, ros_msg.grasp_params) - ros_msg.grasp_params_is_set = proto.HasField("grasp_params") - ros_msg.walk_gaze_mode.value = proto.walk_gaze_mode - - -def convert_bosdyn_msgs_pick_object_in_image_to_proto(ros_msg: "bosdyn_msgs.msgs.PickObjectInImage", proto: "bosdyn.api.manipulation_api_pb2.PickObjectInImage") -> None: - proto.Clear() - if ros_msg.pixel_xy_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.pixel_xy, proto.pixel_xy) - if ros_msg.transforms_snapshot_for_camera_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot_for_camera, proto.transforms_snapshot_for_camera) - proto.frame_name_image_sensor = ros_msg.frame_name_image_sensor - if ros_msg.camera_model_is_set: - convert_bosdyn_msgs_image_source_pinhole_model_to_proto(ros_msg.camera_model, proto.camera_model) - if ros_msg.grasp_params_is_set: - convert_bosdyn_msgs_grasp_params_to_proto(ros_msg.grasp_params, proto.grasp_params) - proto.walk_gaze_mode = ros_msg.walk_gaze_mode.value - - -def convert_proto_to_bosdyn_msgs_grasp_params(proto: "bosdyn.api.manipulation_api_pb2.GraspParams", ros_msg: "bosdyn_msgs.msgs.GraspParams") -> None: - ros_msg.grasp_palm_to_fingertip = proto.grasp_palm_to_fingertip - ros_msg.grasp_params_frame_name = proto.grasp_params_frame_name - from bosdyn_msgs.msg import AllowableOrientation - ros_msg.allowable_orientation = [] - for _item in proto.allowable_orientation: - ros_msg.allowable_orientation.append(AllowableOrientation()) - convert_proto_to_bosdyn_msgs_allowable_orientation(_item, ros_msg.allowable_orientation[-1]) - ros_msg.position_constraint.value = proto.position_constraint - ros_msg.manipulation_camera_source.value = proto.manipulation_camera_source - - -def convert_bosdyn_msgs_grasp_params_to_proto(ros_msg: "bosdyn_msgs.msgs.GraspParams", proto: "bosdyn.api.manipulation_api_pb2.GraspParams") -> None: - proto.Clear() - proto.grasp_palm_to_fingertip = ros_msg.grasp_palm_to_fingertip - proto.grasp_params_frame_name = ros_msg.grasp_params_frame_name - del proto.allowable_orientation[:] - for _item in ros_msg.allowable_orientation: - convert_bosdyn_msgs_allowable_orientation_to_proto(_item, proto.allowable_orientation.add()) - proto.position_constraint = ros_msg.position_constraint.value - proto.manipulation_camera_source = ros_msg.manipulation_camera_source.value - - -def convert_proto_to_bosdyn_msgs_grasp_position_constraint(proto: "bosdyn.api.manipulation_api_pb2.GraspPositionConstraint", ros_msg: "bosdyn_msgs.msgs.GraspPositionConstraint") -> None: - pass - - -def convert_bosdyn_msgs_grasp_position_constraint_to_proto(ros_msg: "bosdyn_msgs.msgs.GraspPositionConstraint", proto: "bosdyn.api.manipulation_api_pb2.GraspPositionConstraint") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_allowable_orientation_one_of_constraint(proto: "bosdyn.api.manipulation_api_pb2.AllowableOrientation", ros_msg: "bosdyn_msgs.msgs.AllowableOrientationOneOfConstraint") -> None: - if proto.HasField("rotation_with_tolerance"): - ros_msg.constraint_choice = ros_msg.CONSTRAINT_ROTATION_WITH_TOLERANCE_SET - convert_proto_to_bosdyn_msgs_rotation_with_tolerance(proto.rotation_with_tolerance, ros_msg.rotation_with_tolerance) - if proto.HasField("vector_alignment_with_tolerance"): - ros_msg.constraint_choice = ros_msg.CONSTRAINT_VECTOR_ALIGNMENT_WITH_TOLERANCE_SET - convert_proto_to_bosdyn_msgs_vector_alignment_with_tolerance(proto.vector_alignment_with_tolerance, ros_msg.vector_alignment_with_tolerance) - if proto.HasField("squeeze_grasp"): - ros_msg.constraint_choice = ros_msg.CONSTRAINT_SQUEEZE_GRASP_SET - convert_proto_to_bosdyn_msgs_squeeze_grasp(proto.squeeze_grasp, ros_msg.squeeze_grasp) - - -def convert_bosdyn_msgs_allowable_orientation_one_of_constraint_to_proto(ros_msg: "bosdyn_msgs.msgs.AllowableOrientationOneOfConstraint", proto: "bosdyn.api.manipulation_api_pb2.AllowableOrientation") -> None: - proto.ClearField("constraint") - if ros_msg.constraint_choice == ros_msg.CONSTRAINT_ROTATION_WITH_TOLERANCE_SET: - convert_bosdyn_msgs_rotation_with_tolerance_to_proto(ros_msg.rotation_with_tolerance, proto.rotation_with_tolerance) - if ros_msg.constraint_choice == ros_msg.CONSTRAINT_VECTOR_ALIGNMENT_WITH_TOLERANCE_SET: - convert_bosdyn_msgs_vector_alignment_with_tolerance_to_proto(ros_msg.vector_alignment_with_tolerance, proto.vector_alignment_with_tolerance) - if ros_msg.constraint_choice == ros_msg.CONSTRAINT_SQUEEZE_GRASP_SET: - convert_bosdyn_msgs_squeeze_grasp_to_proto(ros_msg.squeeze_grasp, proto.squeeze_grasp) - - -def convert_proto_to_bosdyn_msgs_allowable_orientation(proto: "bosdyn.api.manipulation_api_pb2.AllowableOrientation", ros_msg: "bosdyn_msgs.msgs.AllowableOrientation") -> None: - convert_proto_to_bosdyn_msgs_allowable_orientation_one_of_constraint(proto, ros_msg.constraint) - - -def convert_bosdyn_msgs_allowable_orientation_to_proto(ros_msg: "bosdyn_msgs.msgs.AllowableOrientation", proto: "bosdyn.api.manipulation_api_pb2.AllowableOrientation") -> None: - proto.Clear() - convert_bosdyn_msgs_allowable_orientation_one_of_constraint_to_proto(ros_msg.constraint, proto) - - -def convert_proto_to_bosdyn_msgs_rotation_with_tolerance(proto: "bosdyn.api.manipulation_api_pb2.RotationWithTolerance", ros_msg: "bosdyn_msgs.msgs.RotationWithTolerance") -> None: - convert_proto_to_geometry_msgs_quaternion(proto.rotation_ewrt_frame, ros_msg.rotation_ewrt_frame) - ros_msg.rotation_ewrt_frame_is_set = proto.HasField("rotation_ewrt_frame") - ros_msg.threshold_radians = proto.threshold_radians - - -def convert_bosdyn_msgs_rotation_with_tolerance_to_proto(ros_msg: "bosdyn_msgs.msgs.RotationWithTolerance", proto: "bosdyn.api.manipulation_api_pb2.RotationWithTolerance") -> None: - proto.Clear() - if ros_msg.rotation_ewrt_frame_is_set: - convert_geometry_msgs_quaternion_to_proto(ros_msg.rotation_ewrt_frame, proto.rotation_ewrt_frame) - proto.threshold_radians = ros_msg.threshold_radians - - -def convert_proto_to_bosdyn_msgs_vector_alignment_with_tolerance(proto: "bosdyn.api.manipulation_api_pb2.VectorAlignmentWithTolerance", ros_msg: "bosdyn_msgs.msgs.VectorAlignmentWithTolerance") -> None: - convert_proto_to_geometry_msgs_vector3(proto.axis_on_gripper_ewrt_gripper, ros_msg.axis_on_gripper_ewrt_gripper) - ros_msg.axis_on_gripper_ewrt_gripper_is_set = proto.HasField("axis_on_gripper_ewrt_gripper") - convert_proto_to_geometry_msgs_vector3(proto.axis_to_align_with_ewrt_frame, ros_msg.axis_to_align_with_ewrt_frame) - ros_msg.axis_to_align_with_ewrt_frame_is_set = proto.HasField("axis_to_align_with_ewrt_frame") - ros_msg.threshold_radians = proto.threshold_radians - - -def convert_bosdyn_msgs_vector_alignment_with_tolerance_to_proto(ros_msg: "bosdyn_msgs.msgs.VectorAlignmentWithTolerance", proto: "bosdyn.api.manipulation_api_pb2.VectorAlignmentWithTolerance") -> None: - proto.Clear() - if ros_msg.axis_on_gripper_ewrt_gripper_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.axis_on_gripper_ewrt_gripper, proto.axis_on_gripper_ewrt_gripper) - if ros_msg.axis_to_align_with_ewrt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.axis_to_align_with_ewrt_frame, proto.axis_to_align_with_ewrt_frame) - proto.threshold_radians = ros_msg.threshold_radians - - -def convert_proto_to_bosdyn_msgs_squeeze_grasp(proto: "bosdyn.api.manipulation_api_pb2.SqueezeGrasp", ros_msg: "bosdyn_msgs.msgs.SqueezeGrasp") -> None: - ros_msg.squeeze_grasp_disallowed = proto.squeeze_grasp_disallowed - - -def convert_bosdyn_msgs_squeeze_grasp_to_proto(ros_msg: "bosdyn_msgs.msgs.SqueezeGrasp", proto: "bosdyn.api.manipulation_api_pb2.SqueezeGrasp") -> None: - proto.Clear() - proto.squeeze_grasp_disallowed = ros_msg.squeeze_grasp_disallowed - - -def convert_proto_to_bosdyn_msgs_manipulation_api_feedback_request(proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.ManipulationApiFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.manipulation_cmd_id = proto.manipulation_cmd_id - - -def convert_bosdyn_msgs_manipulation_api_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationApiFeedbackRequest", proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.manipulation_cmd_id = ros_msg.manipulation_cmd_id - - -def convert_proto_to_bosdyn_msgs_manipulation_api_feedback_response(proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.ManipulationApiFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.manipulation_cmd_id = proto.manipulation_cmd_id - ros_msg.current_state.value = proto.current_state - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot_manipulation_data, ros_msg.transforms_snapshot_manipulation_data) - ros_msg.transforms_snapshot_manipulation_data_is_set = proto.HasField("transforms_snapshot_manipulation_data") - - -def convert_bosdyn_msgs_manipulation_api_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationApiFeedbackResponse", proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.manipulation_cmd_id = ros_msg.manipulation_cmd_id - proto.current_state = ros_msg.current_state.value - if ros_msg.transforms_snapshot_manipulation_data_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot_manipulation_data, proto.transforms_snapshot_manipulation_data) - - -def convert_proto_to_bosdyn_msgs_manipulation_api_response(proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiResponse", ros_msg: "bosdyn_msgs.msgs.ManipulationApiResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.manipulation_cmd_id = proto.manipulation_cmd_id - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_manipulation_api_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationApiResponse", proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.manipulation_cmd_id = ros_msg.manipulation_cmd_id - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_manipulation_feedback_state(proto: "bosdyn.api.manipulation_api_pb2.ManipulationFeedbackState", ros_msg: "bosdyn_msgs.msgs.ManipulationFeedbackState") -> None: - pass - - -def convert_bosdyn_msgs_manipulation_feedback_state_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationFeedbackState", proto: "bosdyn.api.manipulation_api_pb2.ManipulationFeedbackState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_manipulation_camera_source(proto: "bosdyn.api.manipulation_api_pb2.ManipulationCameraSource", ros_msg: "bosdyn_msgs.msgs.ManipulationCameraSource") -> None: - pass - - -def convert_bosdyn_msgs_manipulation_camera_source_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationCameraSource", proto: "bosdyn.api.manipulation_api_pb2.ManipulationCameraSource") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_walk_gaze_mode(proto: "bosdyn.api.manipulation_api_pb2.WalkGazeMode", ros_msg: "bosdyn_msgs.msgs.WalkGazeMode") -> None: - pass - - -def convert_bosdyn_msgs_walk_gaze_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.WalkGazeMode", proto: "bosdyn.api.manipulation_api_pb2.WalkGazeMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_manipulation_api_request_one_of_manipulation_cmd(proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiRequest", ros_msg: "bosdyn_msgs.msgs.ManipulationApiRequestOneOfManipulationCmd") -> None: - if proto.HasField("walk_to_object_ray_in_world"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_WALK_TO_OBJECT_RAY_IN_WORLD_SET - convert_proto_to_bosdyn_msgs_walk_to_object_ray_in_world(proto.walk_to_object_ray_in_world, ros_msg.walk_to_object_ray_in_world) - if proto.HasField("walk_to_object_in_image"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_WALK_TO_OBJECT_IN_IMAGE_SET - convert_proto_to_bosdyn_msgs_walk_to_object_in_image(proto.walk_to_object_in_image, ros_msg.walk_to_object_in_image) - if proto.HasField("pick_object"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_PICK_OBJECT_SET - convert_proto_to_bosdyn_msgs_pick_object(proto.pick_object, ros_msg.pick_object) - if proto.HasField("pick_object_in_image"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_PICK_OBJECT_IN_IMAGE_SET - convert_proto_to_bosdyn_msgs_pick_object_in_image(proto.pick_object_in_image, ros_msg.pick_object_in_image) - if proto.HasField("pick_object_ray_in_world"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_PICK_OBJECT_RAY_IN_WORLD_SET - convert_proto_to_bosdyn_msgs_pick_object_ray_in_world(proto.pick_object_ray_in_world, ros_msg.pick_object_ray_in_world) - if proto.HasField("pick_object_execute_plan"): - ros_msg.manipulation_cmd_choice = ros_msg.MANIPULATION_CMD_PICK_OBJECT_EXECUTE_PLAN_SET - convert_proto_to_bosdyn_msgs_pick_object_execute_plan(proto.pick_object_execute_plan, ros_msg.pick_object_execute_plan) - - -def convert_bosdyn_msgs_manipulation_api_request_one_of_manipulation_cmd_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationApiRequestOneOfManipulationCmd", proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiRequest") -> None: - proto.ClearField("manipulation_cmd") - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_WALK_TO_OBJECT_RAY_IN_WORLD_SET: - convert_bosdyn_msgs_walk_to_object_ray_in_world_to_proto(ros_msg.walk_to_object_ray_in_world, proto.walk_to_object_ray_in_world) - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_WALK_TO_OBJECT_IN_IMAGE_SET: - convert_bosdyn_msgs_walk_to_object_in_image_to_proto(ros_msg.walk_to_object_in_image, proto.walk_to_object_in_image) - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_PICK_OBJECT_SET: - convert_bosdyn_msgs_pick_object_to_proto(ros_msg.pick_object, proto.pick_object) - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_PICK_OBJECT_IN_IMAGE_SET: - convert_bosdyn_msgs_pick_object_in_image_to_proto(ros_msg.pick_object_in_image, proto.pick_object_in_image) - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_PICK_OBJECT_RAY_IN_WORLD_SET: - convert_bosdyn_msgs_pick_object_ray_in_world_to_proto(ros_msg.pick_object_ray_in_world, proto.pick_object_ray_in_world) - if ros_msg.manipulation_cmd_choice == ros_msg.MANIPULATION_CMD_PICK_OBJECT_EXECUTE_PLAN_SET: - convert_bosdyn_msgs_pick_object_execute_plan_to_proto(ros_msg.pick_object_execute_plan, proto.pick_object_execute_plan) - - -def convert_proto_to_bosdyn_msgs_manipulation_api_request(proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiRequest", ros_msg: "bosdyn_msgs.msgs.ManipulationApiRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_manipulation_api_request_one_of_manipulation_cmd(proto, ros_msg.manipulation_cmd) - - -def convert_bosdyn_msgs_manipulation_api_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulationApiRequest", proto: "bosdyn.api.manipulation_api_pb2.ManipulationApiRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - convert_bosdyn_msgs_manipulation_api_request_one_of_manipulation_cmd_to_proto(ros_msg.manipulation_cmd, proto) - - -def convert_proto_to_bosdyn_msgs_api_grasp_override_override(proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverride.Override", ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideOverride") -> None: - pass - - -def convert_bosdyn_msgs_api_grasp_override_override_to_proto(ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideOverride", proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverride.Override") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_api_grasp_override(proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverride", ros_msg: "bosdyn_msgs.msgs.ApiGraspOverride") -> None: - ros_msg.override_request.value = proto.override_request - - -def convert_bosdyn_msgs_api_grasp_override_to_proto(ros_msg: "bosdyn_msgs.msgs.ApiGraspOverride", proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverride") -> None: - proto.Clear() - proto.override_request = ros_msg.override_request.value - - -def convert_proto_to_bosdyn_msgs_api_grasped_carry_state_override(proto: "bosdyn.api.manipulation_api_pb2.ApiGraspedCarryStateOverride", ros_msg: "bosdyn_msgs.msgs.ApiGraspedCarryStateOverride") -> None: - ros_msg.override_request.value = proto.override_request - - -def convert_bosdyn_msgs_api_grasped_carry_state_override_to_proto(ros_msg: "bosdyn_msgs.msgs.ApiGraspedCarryStateOverride", proto: "bosdyn.api.manipulation_api_pb2.ApiGraspedCarryStateOverride") -> None: - proto.Clear() - proto.override_request = ros_msg.override_request.value - - -def convert_proto_to_bosdyn_msgs_api_grasp_override_request(proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverrideRequest", ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_api_grasp_override(proto.api_grasp_override, ros_msg.api_grasp_override) - ros_msg.api_grasp_override_is_set = proto.HasField("api_grasp_override") - convert_proto_to_bosdyn_msgs_api_grasped_carry_state_override(proto.carry_state_override, ros_msg.carry_state_override) - ros_msg.carry_state_override_is_set = proto.HasField("carry_state_override") - - -def convert_bosdyn_msgs_api_grasp_override_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideRequest", proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverrideRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.api_grasp_override_is_set: - convert_bosdyn_msgs_api_grasp_override_to_proto(ros_msg.api_grasp_override, proto.api_grasp_override) - if ros_msg.carry_state_override_is_set: - convert_bosdyn_msgs_api_grasped_carry_state_override_to_proto(ros_msg.carry_state_override, proto.carry_state_override) - - -def convert_proto_to_bosdyn_msgs_api_grasp_override_response(proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverrideResponse", ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_api_grasp_override_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ApiGraspOverrideResponse", proto: "bosdyn.api.manipulation_api_pb2.ApiGraspOverrideResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_state_request_one_of_lower_bound(proto: "bosdyn.api.mission.mission_pb2.GetStateRequest", ros_msg: "bosdyn_msgs.msgs.GetStateRequestOneOfLowerBound") -> None: - if proto.HasField("history_lower_tick_bound"): - ros_msg.lower_bound_choice = ros_msg.LOWER_BOUND_HISTORY_LOWER_TICK_BOUND_SET - ros_msg.history_lower_tick_bound = proto.history_lower_tick_bound - if proto.HasField("history_past_ticks"): - ros_msg.lower_bound_choice = ros_msg.LOWER_BOUND_HISTORY_PAST_TICKS_SET - ros_msg.history_past_ticks = proto.history_past_ticks - - -def convert_bosdyn_msgs_get_state_request_one_of_lower_bound_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStateRequestOneOfLowerBound", proto: "bosdyn.api.mission.mission_pb2.GetStateRequest") -> None: - proto.ClearField("lower_bound") - if ros_msg.lower_bound_choice == ros_msg.LOWER_BOUND_HISTORY_LOWER_TICK_BOUND_SET: - proto.history_lower_tick_bound = ros_msg.history_lower_tick_bound - if ros_msg.lower_bound_choice == ros_msg.LOWER_BOUND_HISTORY_PAST_TICKS_SET: - proto.history_past_ticks = ros_msg.history_past_ticks - - -def convert_proto_to_bosdyn_msgs_get_state_request(proto: "bosdyn.api.mission.mission_pb2.GetStateRequest", ros_msg: "bosdyn_msgs.msgs.GetStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.history_upper_tick_bound = proto.history_upper_tick_bound.value - ros_msg.history_upper_tick_bound_is_set = proto.HasField("history_upper_tick_bound") - convert_proto_to_bosdyn_msgs_get_state_request_one_of_lower_bound(proto, ros_msg.lower_bound) - - -def convert_bosdyn_msgs_get_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStateRequest", proto: "bosdyn.api.mission.mission_pb2.GetStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.history_upper_tick_bound_is_set: - convert_int64_to_proto(ros_msg.history_upper_tick_bound, proto.history_upper_tick_bound) - convert_bosdyn_msgs_get_state_request_one_of_lower_bound_to_proto(ros_msg.lower_bound, proto) - - -def convert_proto_to_bosdyn_msgs_get_state_response(proto: "bosdyn.api.mission.mission_pb2.GetStateResponse", ros_msg: "bosdyn_msgs.msgs.GetStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_state(proto.state, ros_msg.state) - ros_msg.state_is_set = proto.HasField("state") - - -def convert_bosdyn_msgs_get_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStateResponse", proto: "bosdyn.api.mission.mission_pb2.GetStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.state_is_set: - convert_bosdyn_msgs_state_to_proto(ros_msg.state, proto.state) - - -def convert_proto_to_bosdyn_msgs_state_answered_question(proto: "bosdyn.api.mission.mission_pb2.State.AnsweredQuestion", ros_msg: "bosdyn_msgs.msgs.StateAnsweredQuestion") -> None: - convert_proto_to_bosdyn_msgs_question(proto.question, ros_msg.question) - ros_msg.question_is_set = proto.HasField("question") - ros_msg.accepted_answer_code = proto.accepted_answer_code - - -def convert_bosdyn_msgs_state_answered_question_to_proto(ros_msg: "bosdyn_msgs.msgs.StateAnsweredQuestion", proto: "bosdyn.api.mission.mission_pb2.State.AnsweredQuestion") -> None: - proto.Clear() - if ros_msg.question_is_set: - convert_bosdyn_msgs_question_to_proto(ros_msg.question, proto.question) - proto.accepted_answer_code = ros_msg.accepted_answer_code - - -def convert_proto_to_bosdyn_msgs_state_node_states_at_tick_node_state_blackboard_state(proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick.NodeState.BlackboardState", ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTickNodeStateBlackboardState") -> None: - from bosdyn_msgs.msg import KeyValue - ros_msg.variables = [] - for _item in proto.variables: - ros_msg.variables.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.variables[-1]) - - -def convert_bosdyn_msgs_state_node_states_at_tick_node_state_blackboard_state_to_proto(ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTickNodeStateBlackboardState", proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick.NodeState.BlackboardState") -> None: - proto.Clear() - del proto.variables[:] - for _item in ros_msg.variables: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.variables.add()) - - -def convert_proto_to_bosdyn_msgs_state_node_states_at_tick_node_state(proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick.NodeState", ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTickNodeState") -> None: - ros_msg.result.value = proto.result - ros_msg.error = proto.error - ros_msg.id = proto.id - convert_proto_to_bosdyn_msgs_state_node_states_at_tick_node_state_blackboard_state(proto.blackboard, ros_msg.blackboard) - ros_msg.blackboard_is_set = proto.HasField("blackboard") - - -def convert_bosdyn_msgs_state_node_states_at_tick_node_state_to_proto(ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTickNodeState", proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick.NodeState") -> None: - proto.Clear() - proto.result = ros_msg.result.value - proto.error = ros_msg.error - proto.id = ros_msg.id - if ros_msg.blackboard_is_set: - convert_bosdyn_msgs_state_node_states_at_tick_node_state_blackboard_state_to_proto(ros_msg.blackboard, proto.blackboard) - - -def convert_proto_to_bosdyn_msgs_state_node_states_at_tick(proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick", ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTick") -> None: - ros_msg.tick_counter = proto.tick_counter - convert_proto_to_builtin_interfaces_time(proto.tick_start_timestamp, ros_msg.tick_start_timestamp) - ros_msg.tick_start_timestamp_is_set = proto.HasField("tick_start_timestamp") - from bosdyn_msgs.msg import StateNodeStatesAtTickNodeState - ros_msg.node_states = [] - for _item in proto.node_states: - ros_msg.node_states.append(StateNodeStatesAtTickNodeState()) - convert_proto_to_bosdyn_msgs_state_node_states_at_tick_node_state(_item, ros_msg.node_states[-1]) - - -def convert_bosdyn_msgs_state_node_states_at_tick_to_proto(ros_msg: "bosdyn_msgs.msgs.StateNodeStatesAtTick", proto: "bosdyn.api.mission.mission_pb2.State.NodeStatesAtTick") -> None: - proto.Clear() - proto.tick_counter = ros_msg.tick_counter - if ros_msg.tick_start_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.tick_start_timestamp, proto.tick_start_timestamp) - del proto.node_states[:] - for _item in ros_msg.node_states: - convert_bosdyn_msgs_state_node_states_at_tick_node_state_to_proto(_item, proto.node_states.add()) - - -def convert_proto_to_bosdyn_msgs_state_status(proto: "bosdyn.api.mission.mission_pb2.State.Status", ros_msg: "bosdyn_msgs.msgs.StateStatus") -> None: - pass - - -def convert_bosdyn_msgs_state_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StateStatus", proto: "bosdyn.api.mission.mission_pb2.State.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_state(proto: "bosdyn.api.mission.mission_pb2.State", ros_msg: "bosdyn_msgs.msgs.State") -> None: - from bosdyn_msgs.msg import Question - ros_msg.questions = [] - for _item in proto.questions: - ros_msg.questions.append(Question()) - convert_proto_to_bosdyn_msgs_question(_item, ros_msg.questions[-1]) - from bosdyn_msgs.msg import StateAnsweredQuestion - ros_msg.answered_questions = [] - for _item in proto.answered_questions: - ros_msg.answered_questions.append(StateAnsweredQuestion()) - convert_proto_to_bosdyn_msgs_state_answered_question(_item, ros_msg.answered_questions[-1]) - from bosdyn_msgs.msg import StateNodeStatesAtTick - ros_msg.history = [] - for _item in proto.history: - ros_msg.history.append(StateNodeStatesAtTick()) - convert_proto_to_bosdyn_msgs_state_node_states_at_tick(_item, ros_msg.history[-1]) - ros_msg.status.value = proto.status - ros_msg.error = proto.error - ros_msg.tick_counter = proto.tick_counter - ros_msg.mission_id = proto.mission_id - - -def convert_bosdyn_msgs_state_to_proto(ros_msg: "bosdyn_msgs.msgs.State", proto: "bosdyn.api.mission.mission_pb2.State") -> None: - proto.Clear() - del proto.questions[:] - for _item in ros_msg.questions: - convert_bosdyn_msgs_question_to_proto(_item, proto.questions.add()) - del proto.answered_questions[:] - for _item in ros_msg.answered_questions: - convert_bosdyn_msgs_state_answered_question_to_proto(_item, proto.answered_questions.add()) - del proto.history[:] - for _item in ros_msg.history: - convert_bosdyn_msgs_state_node_states_at_tick_to_proto(_item, proto.history.add()) - proto.status = ros_msg.status.value - proto.error = ros_msg.error - proto.tick_counter = ros_msg.tick_counter - proto.mission_id = ros_msg.mission_id - - -def convert_proto_to_bosdyn_msgs_question(proto: "bosdyn.api.mission.mission_pb2.Question", ros_msg: "bosdyn_msgs.msgs.Question") -> None: - ros_msg.id = proto.id - ros_msg.source = proto.source - ros_msg.text = proto.text - from bosdyn_msgs.msg import PromptOption - ros_msg.options = [] - for _item in proto.options: - ros_msg.options.append(PromptOption()) - convert_proto_to_bosdyn_msgs_prompt_option(_item, ros_msg.options[-1]) - ros_msg.for_autonomous_processing = proto.for_autonomous_processing - ros_msg.severity.value = proto.severity - - -def convert_bosdyn_msgs_question_to_proto(ros_msg: "bosdyn_msgs.msgs.Question", proto: "bosdyn.api.mission.mission_pb2.Question") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.source = ros_msg.source - proto.text = ros_msg.text - del proto.options[:] - for _item in ros_msg.options: - convert_bosdyn_msgs_prompt_option_to_proto(_item, proto.options.add()) - proto.for_autonomous_processing = ros_msg.for_autonomous_processing - proto.severity = ros_msg.severity.value - - -def convert_proto_to_bosdyn_msgs_answer_question_request(proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionRequest", ros_msg: "bosdyn_msgs.msgs.AnswerQuestionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.question_id = proto.question_id - ros_msg.code = proto.code - - -def convert_bosdyn_msgs_answer_question_request_to_proto(ros_msg: "bosdyn_msgs.msgs.AnswerQuestionRequest", proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.question_id = ros_msg.question_id - proto.code = ros_msg.code - - -def convert_proto_to_bosdyn_msgs_answer_question_response_status(proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionResponse.Status", ros_msg: "bosdyn_msgs.msgs.AnswerQuestionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_answer_question_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.AnswerQuestionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_answer_question_response(proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionResponse", ros_msg: "bosdyn_msgs.msgs.AnswerQuestionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_answer_question_response_to_proto(ros_msg: "bosdyn_msgs.msgs.AnswerQuestionResponse", proto: "bosdyn.api.mission.mission_pb2.AnswerQuestionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_mission_info(proto: "bosdyn.api.mission.mission_pb2.MissionInfo", ros_msg: "bosdyn_msgs.msgs.MissionInfo") -> None: - ros_msg.id = proto.id - convert_proto_to_bosdyn_msgs_node_info(proto.root, ros_msg.root) - ros_msg.root_is_set = proto.HasField("root") - - -def convert_bosdyn_msgs_mission_info_to_proto(ros_msg: "bosdyn_msgs.msgs.MissionInfo", proto: "bosdyn.api.mission.mission_pb2.MissionInfo") -> None: - proto.Clear() - proto.id = ros_msg.id - if ros_msg.root_is_set: - convert_bosdyn_msgs_node_info_to_proto(ros_msg.root, proto.root) - - -def convert_proto_to_bosdyn_msgs_node_info(proto: "bosdyn.api.mission.mission_pb2.NodeInfo", ros_msg: "bosdyn_msgs.msgs.NodeInfo") -> None: - ros_msg.id = proto.id - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_user_data(proto.user_data, ros_msg.user_data) - ros_msg.user_data_is_set = proto.HasField("user_data") - from bosdyn_msgs.msg import SerializedMessage - ros_msg.children = [] - for _item in proto.children: - ros_msg.children.append(SerializedMessage()) - convert_proto_to_serialized_bosdyn_msgs_node_info(_item, ros_msg.children[-1]) - - -def convert_bosdyn_msgs_node_info_to_proto(ros_msg: "bosdyn_msgs.msgs.NodeInfo", proto: "bosdyn.api.mission.mission_pb2.NodeInfo") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.name = ros_msg.name - if ros_msg.user_data_is_set: - convert_bosdyn_msgs_user_data_to_proto(ros_msg.user_data, proto.user_data) - del proto.children[:] - for _item in ros_msg.children: - convert_serialized_bosdyn_msgs_node_info_to_proto(_item, proto.children.add()) - - -def convert_proto_to_bosdyn_msgs_failed_node(proto: "bosdyn.api.mission.mission_pb2.FailedNode", ros_msg: "bosdyn_msgs.msgs.FailedNode") -> None: - ros_msg.name = proto.name - ros_msg.error = proto.error - ros_msg.impl_typename = proto.impl_typename - - -def convert_bosdyn_msgs_failed_node_to_proto(ros_msg: "bosdyn_msgs.msgs.FailedNode", proto: "bosdyn.api.mission.mission_pb2.FailedNode") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.error = ros_msg.error - proto.impl_typename = ros_msg.impl_typename - - -def convert_proto_to_bosdyn_msgs_play_mission_request(proto: "bosdyn.api.mission.mission_pb2.PlayMissionRequest", ros_msg: "bosdyn_msgs.msgs.PlayMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_time(proto.pause_time, ros_msg.pause_time) - ros_msg.pause_time_is_set = proto.HasField("pause_time") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_play_settings(proto.settings, ros_msg.settings) - ros_msg.settings_is_set = proto.HasField("settings") - - -def convert_bosdyn_msgs_play_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PlayMissionRequest", proto: "bosdyn.api.mission.mission_pb2.PlayMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.pause_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.pause_time, proto.pause_time) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.settings_is_set: - convert_bosdyn_msgs_play_settings_to_proto(ros_msg.settings, proto.settings) - - -def convert_proto_to_bosdyn_msgs_play_settings(proto: "bosdyn.api.mission.mission_pb2.PlaySettings", ros_msg: "bosdyn_msgs.msgs.PlaySettings") -> None: - convert_proto_to_bosdyn_msgs_se2_velocity_limit(proto.velocity_limit, ros_msg.velocity_limit) - ros_msg.velocity_limit_is_set = proto.HasField("velocity_limit") - ros_msg.disable_directed_exploration = proto.disable_directed_exploration - ros_msg.disable_alternate_route_finding = proto.disable_alternate_route_finding - ros_msg.path_following_mode.value = proto.path_following_mode - ros_msg.ground_clutter_mode.value = proto.ground_clutter_mode - - -def convert_bosdyn_msgs_play_settings_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaySettings", proto: "bosdyn.api.mission.mission_pb2.PlaySettings") -> None: - proto.Clear() - if ros_msg.velocity_limit_is_set: - convert_bosdyn_msgs_se2_velocity_limit_to_proto(ros_msg.velocity_limit, proto.velocity_limit) - proto.disable_directed_exploration = ros_msg.disable_directed_exploration - proto.disable_alternate_route_finding = ros_msg.disable_alternate_route_finding - proto.path_following_mode = ros_msg.path_following_mode.value - proto.ground_clutter_mode = ros_msg.ground_clutter_mode.value - - -def convert_proto_to_bosdyn_msgs_play_mission_response_status(proto: "bosdyn.api.mission.mission_pb2.PlayMissionResponse.Status", ros_msg: "bosdyn_msgs.msgs.PlayMissionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_play_mission_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PlayMissionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.PlayMissionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_play_mission_response(proto: "bosdyn.api.mission.mission_pb2.PlayMissionResponse", ros_msg: "bosdyn_msgs.msgs.PlayMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - - -def convert_bosdyn_msgs_play_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PlayMissionResponse", proto: "bosdyn.api.mission.mission_pb2.PlayMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - - -def convert_proto_to_bosdyn_msgs_restart_mission_request(proto: "bosdyn.api.mission.mission_pb2.RestartMissionRequest", ros_msg: "bosdyn_msgs.msgs.RestartMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_builtin_interfaces_time(proto.pause_time, ros_msg.pause_time) - ros_msg.pause_time_is_set = proto.HasField("pause_time") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - convert_proto_to_bosdyn_msgs_play_settings(proto.settings, ros_msg.settings) - ros_msg.settings_is_set = proto.HasField("settings") - - -def convert_bosdyn_msgs_restart_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RestartMissionRequest", proto: "bosdyn.api.mission.mission_pb2.RestartMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.pause_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.pause_time, proto.pause_time) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - if ros_msg.settings_is_set: - convert_bosdyn_msgs_play_settings_to_proto(ros_msg.settings, proto.settings) - - -def convert_proto_to_bosdyn_msgs_restart_mission_response_status(proto: "bosdyn.api.mission.mission_pb2.RestartMissionResponse.Status", ros_msg: "bosdyn_msgs.msgs.RestartMissionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_restart_mission_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RestartMissionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.RestartMissionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_restart_mission_response(proto: "bosdyn.api.mission.mission_pb2.RestartMissionResponse", ros_msg: "bosdyn_msgs.msgs.RestartMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - from bosdyn_msgs.msg import FailedNode - ros_msg.failed_nodes = [] - for _item in proto.failed_nodes: - ros_msg.failed_nodes.append(FailedNode()) - convert_proto_to_bosdyn_msgs_failed_node(_item, ros_msg.failed_nodes[-1]) - - -def convert_bosdyn_msgs_restart_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RestartMissionResponse", proto: "bosdyn.api.mission.mission_pb2.RestartMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - del proto.failed_nodes[:] - for _item in ros_msg.failed_nodes: - convert_bosdyn_msgs_failed_node_to_proto(_item, proto.failed_nodes.add()) - - -def convert_proto_to_bosdyn_msgs_load_mission_request(proto: "bosdyn.api.mission.mission_pb2.LoadMissionRequest", ros_msg: "bosdyn_msgs.msgs.LoadMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_node(proto.root, ros_msg.root) - ros_msg.root_is_set = proto.HasField("root") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - - -def convert_bosdyn_msgs_load_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadMissionRequest", proto: "bosdyn.api.mission.mission_pb2.LoadMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.root_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.root, proto.root) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - - -def convert_proto_to_bosdyn_msgs_load_mission_response_status(proto: "bosdyn.api.mission.mission_pb2.LoadMissionResponse.Status", ros_msg: "bosdyn_msgs.msgs.LoadMissionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_load_mission_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadMissionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.LoadMissionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_load_mission_response(proto: "bosdyn.api.mission.mission_pb2.LoadMissionResponse", ros_msg: "bosdyn_msgs.msgs.LoadMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - convert_proto_to_bosdyn_msgs_mission_info(proto.mission_info, ros_msg.mission_info) - ros_msg.mission_info_is_set = proto.HasField("mission_info") - from bosdyn_msgs.msg import FailedNode - ros_msg.failed_nodes = [] - for _item in proto.failed_nodes: - ros_msg.failed_nodes.append(FailedNode()) - convert_proto_to_bosdyn_msgs_failed_node(_item, ros_msg.failed_nodes[-1]) - - -def convert_bosdyn_msgs_load_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadMissionResponse", proto: "bosdyn.api.mission.mission_pb2.LoadMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - if ros_msg.mission_info_is_set: - convert_bosdyn_msgs_mission_info_to_proto(ros_msg.mission_info, proto.mission_info) - del proto.failed_nodes[:] - for _item in ros_msg.failed_nodes: - convert_bosdyn_msgs_failed_node_to_proto(_item, proto.failed_nodes.add()) - - -def convert_proto_to_bosdyn_msgs_get_info_request(proto: "bosdyn.api.mission.mission_pb2.GetInfoRequest", ros_msg: "bosdyn_msgs.msgs.GetInfoRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_info_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetInfoRequest", proto: "bosdyn.api.mission.mission_pb2.GetInfoRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_info_response(proto: "bosdyn.api.mission.mission_pb2.GetInfoResponse", ros_msg: "bosdyn_msgs.msgs.GetInfoResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_mission_info(proto.mission_info, ros_msg.mission_info) - ros_msg.mission_info_is_set = proto.HasField("mission_info") - - -def convert_bosdyn_msgs_get_info_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetInfoResponse", proto: "bosdyn.api.mission.mission_pb2.GetInfoResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.mission_info_is_set: - convert_bosdyn_msgs_mission_info_to_proto(ros_msg.mission_info, proto.mission_info) - - -def convert_proto_to_bosdyn_msgs_pause_mission_request(proto: "bosdyn.api.mission.mission_pb2.PauseMissionRequest", ros_msg: "bosdyn_msgs.msgs.PauseMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_pause_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PauseMissionRequest", proto: "bosdyn.api.mission.mission_pb2.PauseMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_pause_mission_response_status(proto: "bosdyn.api.mission.mission_pb2.PauseMissionResponse.Status", ros_msg: "bosdyn_msgs.msgs.PauseMissionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_pause_mission_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PauseMissionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.PauseMissionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_pause_mission_response(proto: "bosdyn.api.mission.mission_pb2.PauseMissionResponse", ros_msg: "bosdyn_msgs.msgs.PauseMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_pause_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PauseMissionResponse", proto: "bosdyn.api.mission.mission_pb2.PauseMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_stop_mission_request(proto: "bosdyn.api.mission.mission_pb2.StopMissionRequest", ros_msg: "bosdyn_msgs.msgs.StopMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - - -def convert_bosdyn_msgs_stop_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StopMissionRequest", proto: "bosdyn.api.mission.mission_pb2.StopMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - - -def convert_proto_to_bosdyn_msgs_stop_mission_response_status(proto: "bosdyn.api.mission.mission_pb2.StopMissionResponse.Status", ros_msg: "bosdyn_msgs.msgs.StopMissionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_stop_mission_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StopMissionResponseStatus", proto: "bosdyn.api.mission.mission_pb2.StopMissionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stop_mission_response(proto: "bosdyn.api.mission.mission_pb2.StopMissionResponse", ros_msg: "bosdyn_msgs.msgs.StopMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_stop_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StopMissionResponse", proto: "bosdyn.api.mission.mission_pb2.StopMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_get_mission_request(proto: "bosdyn.api.mission.mission_pb2.GetMissionRequest", ros_msg: "bosdyn_msgs.msgs.GetMissionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_mission_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetMissionRequest", proto: "bosdyn.api.mission.mission_pb2.GetMissionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_mission_response(proto: "bosdyn.api.mission.mission_pb2.GetMissionResponse", ros_msg: "bosdyn_msgs.msgs.GetMissionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_node(proto.root, ros_msg.root) - ros_msg.root_is_set = proto.HasField("root") - ros_msg.id = proto.id - - -def convert_bosdyn_msgs_get_mission_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetMissionResponse", proto: "bosdyn.api.mission.mission_pb2.GetMissionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.root_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.root, proto.root) - proto.id = ros_msg.id - - -def convert_proto_to_bosdyn_msgs_node_one_of_type(proto: "bosdyn.api.mission.nodes_pb2.Node", ros_msg: "bosdyn_msgs.msgs.NodeOneOfType") -> None: - if proto.HasField("node_reference"): - ros_msg.type_choice = ros_msg.TYPE_NODE_REFERENCE_SET - ros_msg.node_reference = proto.node_reference - - -def convert_bosdyn_msgs_node_one_of_type_to_proto(ros_msg: "bosdyn_msgs.msgs.NodeOneOfType", proto: "bosdyn.api.mission.nodes_pb2.Node") -> None: - proto.ClearField("type") - if ros_msg.type_choice == ros_msg.TYPE_NODE_REFERENCE_SET: - proto.node_reference = ros_msg.node_reference - - -def convert_proto_to_bosdyn_msgs_node(proto: "bosdyn.api.mission.nodes_pb2.Node", ros_msg: "bosdyn_msgs.msgs.Node") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_user_data(proto.user_data, ros_msg.user_data) - ros_msg.user_data_is_set = proto.HasField("user_data") - ros_msg.reference_id = proto.reference_id - convert_proto_to_bosdyn_msgs_node_one_of_type(proto, ros_msg.type) - from bosdyn_msgs.msg import KeyValue - ros_msg.parameter_values = [] - for _item in proto.parameter_values: - ros_msg.parameter_values.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.parameter_values[-1]) - from bosdyn_msgs.msg import KeyValue - ros_msg.overrides = [] - for _item in proto.overrides: - ros_msg.overrides.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.overrides[-1]) - from bosdyn_msgs.msg import VariableDeclaration - ros_msg.parameters = [] - for _item in proto.parameters: - ros_msg.parameters.append(VariableDeclaration()) - convert_proto_to_bosdyn_msgs_variable_declaration(_item, ros_msg.parameters[-1]) - - -def convert_bosdyn_msgs_node_to_proto(ros_msg: "bosdyn_msgs.msgs.Node", proto: "bosdyn.api.mission.nodes_pb2.Node") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.user_data_is_set: - convert_bosdyn_msgs_user_data_to_proto(ros_msg.user_data, proto.user_data) - proto.reference_id = ros_msg.reference_id - convert_bosdyn_msgs_node_one_of_type_to_proto(ros_msg.type, proto) - del proto.parameter_values[:] - for _item in ros_msg.parameter_values: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.parameter_values.add()) - del proto.overrides[:] - for _item in ros_msg.overrides: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.overrides.add()) - del proto.parameters[:] - for _item in ros_msg.parameters: - convert_bosdyn_msgs_variable_declaration_to_proto(_item, proto.parameters.add()) - - -def convert_proto_to_bosdyn_msgs_sequence(proto: "bosdyn.api.mission.nodes_pb2.Sequence", ros_msg: "bosdyn_msgs.msgs.Sequence") -> None: - ros_msg.always_restart = proto.always_restart - from bosdyn_msgs.msg import Node - ros_msg.children = [] - for _item in proto.children: - ros_msg.children.append(Node()) - convert_proto_to_bosdyn_msgs_node(_item, ros_msg.children[-1]) - - -def convert_bosdyn_msgs_sequence_to_proto(ros_msg: "bosdyn_msgs.msgs.Sequence", proto: "bosdyn.api.mission.nodes_pb2.Sequence") -> None: - proto.Clear() - proto.always_restart = ros_msg.always_restart - del proto.children[:] - for _item in ros_msg.children: - convert_bosdyn_msgs_node_to_proto(_item, proto.children.add()) - - -def convert_proto_to_bosdyn_msgs_selector(proto: "bosdyn.api.mission.nodes_pb2.Selector", ros_msg: "bosdyn_msgs.msgs.Selector") -> None: - ros_msg.always_restart = proto.always_restart - from bosdyn_msgs.msg import Node - ros_msg.children = [] - for _item in proto.children: - ros_msg.children.append(Node()) - convert_proto_to_bosdyn_msgs_node(_item, ros_msg.children[-1]) - - -def convert_bosdyn_msgs_selector_to_proto(ros_msg: "bosdyn_msgs.msgs.Selector", proto: "bosdyn.api.mission.nodes_pb2.Selector") -> None: - proto.Clear() - proto.always_restart = ros_msg.always_restart - del proto.children[:] - for _item in ros_msg.children: - convert_bosdyn_msgs_node_to_proto(_item, proto.children.add()) - - -def convert_proto_to_bosdyn_msgs_switch(proto: "bosdyn.api.mission.nodes_pb2.Switch", ros_msg: "bosdyn_msgs.msgs.Switch") -> None: - convert_proto_to_bosdyn_msgs_value(proto.pivot_value, ros_msg.pivot_value) - ros_msg.pivot_value_is_set = proto.HasField("pivot_value") - ros_msg.always_restart = proto.always_restart - from bosdyn_msgs.msg import KeyInt32ValueBosdynMsgsNode - ros_msg.int_children = [] - for _item in proto.int_children: - ros_msg.int_children.append(KeyInt32ValueBosdynMsgsNode()) - ros_msg.int_children[-1].key = _item - convert_proto_to_bosdyn_msgs_node(proto.int_children[_item], ros_msg.int_children[-1].value) - convert_proto_to_bosdyn_msgs_node(proto.default_child, ros_msg.default_child) - ros_msg.default_child_is_set = proto.HasField("default_child") - - -def convert_bosdyn_msgs_switch_to_proto(ros_msg: "bosdyn_msgs.msgs.Switch", proto: "bosdyn.api.mission.nodes_pb2.Switch") -> None: - proto.Clear() - if ros_msg.pivot_value_is_set: - convert_bosdyn_msgs_value_to_proto(ros_msg.pivot_value, proto.pivot_value) - proto.always_restart = ros_msg.always_restart - for _item in ros_msg.int_children: - convert_bosdyn_msgs_node_to_proto(_item.value, proto.int_children[_item.key]) - if ros_msg.default_child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.default_child, proto.default_child) - - -def convert_proto_to_bosdyn_msgs_repeat(proto: "bosdyn.api.mission.nodes_pb2.Repeat", ros_msg: "bosdyn_msgs.msgs.Repeat") -> None: - ros_msg.max_starts = proto.max_starts - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.start_counter_state_name = proto.start_counter_state_name - ros_msg.respect_child_failure = proto.respect_child_failure - - -def convert_bosdyn_msgs_repeat_to_proto(ros_msg: "bosdyn_msgs.msgs.Repeat", proto: "bosdyn.api.mission.nodes_pb2.Repeat") -> None: - proto.Clear() - proto.max_starts = ros_msg.max_starts - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.start_counter_state_name = ros_msg.start_counter_state_name - proto.respect_child_failure = ros_msg.respect_child_failure - - -def convert_proto_to_bosdyn_msgs_retry(proto: "bosdyn.api.mission.nodes_pb2.Retry", ros_msg: "bosdyn_msgs.msgs.Retry") -> None: - ros_msg.max_attempts = proto.max_attempts - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.attempt_counter_state_name = proto.attempt_counter_state_name - - -def convert_bosdyn_msgs_retry_to_proto(ros_msg: "bosdyn_msgs.msgs.Retry", proto: "bosdyn.api.mission.nodes_pb2.Retry") -> None: - proto.Clear() - proto.max_attempts = ros_msg.max_attempts - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.attempt_counter_state_name = ros_msg.attempt_counter_state_name - - -def convert_proto_to_bosdyn_msgs_for_duration(proto: "bosdyn.api.mission.nodes_pb2.ForDuration", ros_msg: "bosdyn_msgs.msgs.ForDuration") -> None: - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - ros_msg.duration_is_set = proto.HasField("duration") - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.time_remaining_name = proto.time_remaining_name - convert_proto_to_bosdyn_msgs_node(proto.timeout_child, ros_msg.timeout_child) - ros_msg.timeout_child_is_set = proto.HasField("timeout_child") - - -def convert_bosdyn_msgs_for_duration_to_proto(ros_msg: "bosdyn_msgs.msgs.ForDuration", proto: "bosdyn.api.mission.nodes_pb2.ForDuration") -> None: - proto.Clear() - if ros_msg.duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.time_remaining_name = ros_msg.time_remaining_name - if ros_msg.timeout_child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.timeout_child, proto.timeout_child) - - -def convert_proto_to_bosdyn_msgs_simple_parallel(proto: "bosdyn.api.mission.nodes_pb2.SimpleParallel", ros_msg: "bosdyn_msgs.msgs.SimpleParallel") -> None: - convert_proto_to_bosdyn_msgs_node(proto.primary, ros_msg.primary) - ros_msg.primary_is_set = proto.HasField("primary") - convert_proto_to_bosdyn_msgs_node(proto.secondary, ros_msg.secondary) - ros_msg.secondary_is_set = proto.HasField("secondary") - ros_msg.run_secondary_node_once = proto.run_secondary_node_once - - -def convert_bosdyn_msgs_simple_parallel_to_proto(ros_msg: "bosdyn_msgs.msgs.SimpleParallel", proto: "bosdyn.api.mission.nodes_pb2.SimpleParallel") -> None: - proto.Clear() - if ros_msg.primary_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.primary, proto.primary) - if ros_msg.secondary_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.secondary, proto.secondary) - proto.run_secondary_node_once = ros_msg.run_secondary_node_once - - -def convert_proto_to_bosdyn_msgs_parallel_and(proto: "bosdyn.api.mission.nodes_pb2.ParallelAnd", ros_msg: "bosdyn_msgs.msgs.ParallelAnd") -> None: - from bosdyn_msgs.msg import Node - ros_msg.children = [] - for _item in proto.children: - ros_msg.children.append(Node()) - convert_proto_to_bosdyn_msgs_node(_item, ros_msg.children[-1]) - ros_msg.finish_every_node = proto.finish_every_node - - -def convert_bosdyn_msgs_parallel_and_to_proto(ros_msg: "bosdyn_msgs.msgs.ParallelAnd", proto: "bosdyn.api.mission.nodes_pb2.ParallelAnd") -> None: - proto.Clear() - del proto.children[:] - for _item in ros_msg.children: - convert_bosdyn_msgs_node_to_proto(_item, proto.children.add()) - proto.finish_every_node = ros_msg.finish_every_node - - -def convert_proto_to_bosdyn_msgs_condition_operand_one_of_type(proto: "bosdyn.api.mission.nodes_pb2.Condition.Operand", ros_msg: "bosdyn_msgs.msgs.ConditionOperandOneOfType") -> None: - if proto.HasField("var"): - ros_msg.type_choice = ros_msg.TYPE_VAR_SET - convert_proto_to_bosdyn_msgs_variable_declaration(proto.var, ros_msg.var) - if proto.HasField("const"): - ros_msg.type_choice = ros_msg.TYPE_CONST_SET - convert_proto_to_bosdyn_msgs_constant_value(proto.const, ros_msg.constant) - - -def convert_bosdyn_msgs_condition_operand_one_of_type_to_proto(ros_msg: "bosdyn_msgs.msgs.ConditionOperandOneOfType", proto: "bosdyn.api.mission.nodes_pb2.Condition.Operand") -> None: - proto.ClearField("type") - if ros_msg.type_choice == ros_msg.TYPE_VAR_SET: - convert_bosdyn_msgs_variable_declaration_to_proto(ros_msg.var, proto.var) - if ros_msg.type_choice == ros_msg.TYPE_CONST_SET: - convert_bosdyn_msgs_constant_value_to_proto(ros_msg.constant, proto.const) - - -def convert_proto_to_bosdyn_msgs_condition_operand(proto: "bosdyn.api.mission.nodes_pb2.Condition.Operand", ros_msg: "bosdyn_msgs.msgs.ConditionOperand") -> None: - convert_proto_to_bosdyn_msgs_condition_operand_one_of_type(proto, ros_msg.type) - - -def convert_bosdyn_msgs_condition_operand_to_proto(ros_msg: "bosdyn_msgs.msgs.ConditionOperand", proto: "bosdyn.api.mission.nodes_pb2.Condition.Operand") -> None: - proto.Clear() - convert_bosdyn_msgs_condition_operand_one_of_type_to_proto(ros_msg.type, proto) - - -def convert_proto_to_bosdyn_msgs_condition_compare(proto: "bosdyn.api.mission.nodes_pb2.Condition.Compare", ros_msg: "bosdyn_msgs.msgs.ConditionCompare") -> None: - pass - - -def convert_bosdyn_msgs_condition_compare_to_proto(ros_msg: "bosdyn_msgs.msgs.ConditionCompare", proto: "bosdyn.api.mission.nodes_pb2.Condition.Compare") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_condition_handle_staleness(proto: "bosdyn.api.mission.nodes_pb2.Condition.HandleStaleness", ros_msg: "bosdyn_msgs.msgs.ConditionHandleStaleness") -> None: - pass - - -def convert_bosdyn_msgs_condition_handle_staleness_to_proto(ros_msg: "bosdyn_msgs.msgs.ConditionHandleStaleness", proto: "bosdyn.api.mission.nodes_pb2.Condition.HandleStaleness") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_condition(proto: "bosdyn.api.mission.nodes_pb2.Condition", ros_msg: "bosdyn_msgs.msgs.Condition") -> None: - convert_proto_to_bosdyn_msgs_condition_operand(proto.lhs, ros_msg.lhs) - ros_msg.lhs_is_set = proto.HasField("lhs") - convert_proto_to_bosdyn_msgs_condition_operand(proto.rhs, ros_msg.rhs) - ros_msg.rhs_is_set = proto.HasField("rhs") - ros_msg.operation.value = proto.operation - ros_msg.handle_staleness.value = proto.handle_staleness - - -def convert_bosdyn_msgs_condition_to_proto(ros_msg: "bosdyn_msgs.msgs.Condition", proto: "bosdyn.api.mission.nodes_pb2.Condition") -> None: - proto.Clear() - if ros_msg.lhs_is_set: - convert_bosdyn_msgs_condition_operand_to_proto(ros_msg.lhs, proto.lhs) - if ros_msg.rhs_is_set: - convert_bosdyn_msgs_condition_operand_to_proto(ros_msg.rhs, proto.rhs) - proto.operation = ros_msg.operation.value - proto.handle_staleness = ros_msg.handle_staleness.value - - -def convert_proto_to_bosdyn_msgs_bosdyn_robot_state(proto: "bosdyn.api.mission.nodes_pb2.BosdynRobotState", ros_msg: "bosdyn_msgs.msgs.BosdynRobotState") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.state_name = proto.state_name - - -def convert_bosdyn_msgs_bosdyn_robot_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynRobotState", proto: "bosdyn.api.mission.nodes_pb2.BosdynRobotState") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.state_name = ros_msg.state_name - - -def convert_proto_to_bosdyn_msgs_bosdyn_dock_state(proto: "bosdyn.api.mission.nodes_pb2.BosdynDockState", ros_msg: "bosdyn_msgs.msgs.BosdynDockState") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.state_name = proto.state_name - - -def convert_bosdyn_msgs_bosdyn_dock_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynDockState", proto: "bosdyn.api.mission.nodes_pb2.BosdynDockState") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.state_name = ros_msg.state_name - - -def convert_proto_to_bosdyn_msgs_bosdyn_robot_command(proto: "bosdyn.api.mission.nodes_pb2.BosdynRobotCommand", ros_msg: "bosdyn_msgs.msgs.BosdynRobotCommand") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_robot_command(proto.command, ros_msg.command) - ros_msg.command_is_set = proto.HasField("command") - - -def convert_bosdyn_msgs_bosdyn_robot_command_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynRobotCommand", proto: "bosdyn.api.mission.nodes_pb2.BosdynRobotCommand") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.command_is_set: - convert_bosdyn_msgs_robot_command_to_proto(ros_msg.command, proto.command) - - -def convert_proto_to_bosdyn_msgs_bosdyn_power_request(proto: "bosdyn.api.mission.nodes_pb2.BosdynPowerRequest", ros_msg: "bosdyn_msgs.msgs.BosdynPowerRequest") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - ros_msg.request.value = proto.request - - -def convert_bosdyn_msgs_bosdyn_power_request_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynPowerRequest", proto: "bosdyn.api.mission.nodes_pb2.BosdynPowerRequest") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - proto.request = ros_msg.request.value - - -def convert_proto_to_bosdyn_msgs_bosdyn_navigate_to(proto: "bosdyn.api.mission.nodes_pb2.BosdynNavigateTo", ros_msg: "bosdyn_msgs.msgs.BosdynNavigateTo") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - ros_msg.destination_waypoint_id = proto.destination_waypoint_id - convert_proto_to_bosdyn_msgs_route_gen_params(proto.route_gen_params, ros_msg.route_gen_params) - ros_msg.route_gen_params_is_set = proto.HasField("route_gen_params") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - ros_msg.navigation_feedback_response_blackboard_key = proto.navigation_feedback_response_blackboard_key - ros_msg.navigate_to_response_blackboard_key = proto.navigate_to_response_blackboard_key - ros_msg.route_blocked_behavior.value = proto.route_blocked_behavior - - -def convert_bosdyn_msgs_bosdyn_navigate_to_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynNavigateTo", proto: "bosdyn.api.mission.nodes_pb2.BosdynNavigateTo") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - proto.destination_waypoint_id = ros_msg.destination_waypoint_id - if ros_msg.route_gen_params_is_set: - convert_bosdyn_msgs_route_gen_params_to_proto(ros_msg.route_gen_params, proto.route_gen_params) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - proto.navigation_feedback_response_blackboard_key = ros_msg.navigation_feedback_response_blackboard_key - proto.navigate_to_response_blackboard_key = ros_msg.navigate_to_response_blackboard_key - proto.route_blocked_behavior = ros_msg.route_blocked_behavior.value - - -def convert_proto_to_bosdyn_msgs_bosdyn_navigate_route(proto: "bosdyn.api.mission.nodes_pb2.BosdynNavigateRoute", ros_msg: "bosdyn_msgs.msgs.BosdynNavigateRoute") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_route(proto.route, ros_msg.route) - ros_msg.route_is_set = proto.HasField("route") - convert_proto_to_bosdyn_msgs_route_following_params(proto.route_follow_params, ros_msg.route_follow_params) - ros_msg.route_follow_params_is_set = proto.HasField("route_follow_params") - convert_proto_to_bosdyn_msgs_travel_params(proto.travel_params, ros_msg.travel_params) - ros_msg.travel_params_is_set = proto.HasField("travel_params") - ros_msg.navigation_feedback_response_blackboard_key = proto.navigation_feedback_response_blackboard_key - ros_msg.navigate_route_response_blackboard_key = proto.navigate_route_response_blackboard_key - - -def convert_bosdyn_msgs_bosdyn_navigate_route_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynNavigateRoute", proto: "bosdyn.api.mission.nodes_pb2.BosdynNavigateRoute") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.route_is_set: - convert_bosdyn_msgs_route_to_proto(ros_msg.route, proto.route) - if ros_msg.route_follow_params_is_set: - convert_bosdyn_msgs_route_following_params_to_proto(ros_msg.route_follow_params, proto.route_follow_params) - if ros_msg.travel_params_is_set: - convert_bosdyn_msgs_travel_params_to_proto(ros_msg.travel_params, proto.travel_params) - proto.navigation_feedback_response_blackboard_key = ros_msg.navigation_feedback_response_blackboard_key - proto.navigate_route_response_blackboard_key = ros_msg.navigate_route_response_blackboard_key - - -def convert_proto_to_bosdyn_msgs_bosdyn_graph_nav_state(proto: "bosdyn.api.mission.nodes_pb2.BosdynGraphNavState", ros_msg: "bosdyn_msgs.msgs.BosdynGraphNavState") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.state_name = proto.state_name - ros_msg.waypoint_id = proto.waypoint_id - - -def convert_bosdyn_msgs_bosdyn_graph_nav_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynGraphNavState", proto: "bosdyn.api.mission.nodes_pb2.BosdynGraphNavState") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.state_name = ros_msg.state_name - proto.waypoint_id = ros_msg.waypoint_id - - -def convert_proto_to_bosdyn_msgs_bosdyn_graph_nav_localize(proto: "bosdyn.api.mission.nodes_pb2.BosdynGraphNavLocalize", ros_msg: "bosdyn_msgs.msgs.BosdynGraphNavLocalize") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_set_localization_request(proto.localization_request, ros_msg.localization_request) - ros_msg.localization_request_is_set = proto.HasField("localization_request") - ros_msg.allow_bad_quality = proto.allow_bad_quality - ros_msg.response_bb_key = proto.response_bb_key - - -def convert_bosdyn_msgs_bosdyn_graph_nav_localize_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynGraphNavLocalize", proto: "bosdyn.api.mission.nodes_pb2.BosdynGraphNavLocalize") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.localization_request_is_set: - convert_bosdyn_msgs_set_localization_request_to_proto(ros_msg.localization_request, proto.localization_request) - proto.allow_bad_quality = ros_msg.allow_bad_quality - proto.response_bb_key = ros_msg.response_bb_key - - -def convert_proto_to_bosdyn_msgs_bosdyn_record_event(proto: "bosdyn.api.mission.nodes_pb2.BosdynRecordEvent", ros_msg: "bosdyn_msgs.msgs.BosdynRecordEvent") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_event(proto.event, ros_msg.event) - ros_msg.event_is_set = proto.HasField("event") - ros_msg.succeed_early = proto.succeed_early - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsValue - ros_msg.additional_parameters = [] - for _item in proto.additional_parameters: - ros_msg.additional_parameters.append(KeyStringValueBosdynMsgsValue()) - ros_msg.additional_parameters[-1].key = _item - convert_proto_to_bosdyn_msgs_value(proto.additional_parameters[_item], ros_msg.additional_parameters[-1].value) - - -def convert_bosdyn_msgs_bosdyn_record_event_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynRecordEvent", proto: "bosdyn.api.mission.nodes_pb2.BosdynRecordEvent") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.event_is_set: - convert_bosdyn_msgs_event_to_proto(ros_msg.event, proto.event) - proto.succeed_early = ros_msg.succeed_early - for _item in ros_msg.additional_parameters: - convert_bosdyn_msgs_value_to_proto(_item.value, proto.additional_parameters[_item.key]) - - -def convert_proto_to_bosdyn_msgs_remote_grpc(proto: "bosdyn.api.mission.nodes_pb2.RemoteGrpc", ros_msg: "bosdyn_msgs.msgs.RemoteGrpc") -> None: - ros_msg.host = proto.host - ros_msg.service_name = proto.service_name - ros_msg.timeout = proto.timeout - ros_msg.lease_resources = [] - for _item in proto.lease_resources: - ros_msg.lease_resources.append(_item) - from bosdyn_msgs.msg import KeyValue - ros_msg.inputs = [] - for _item in proto.inputs: - ros_msg.inputs.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.inputs[-1]) - ros_msg.group_name_format = proto.group_name_format - convert_proto_to_bosdyn_msgs_dict_param(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_remote_grpc_to_proto(ros_msg: "bosdyn_msgs.msgs.RemoteGrpc", proto: "bosdyn.api.mission.nodes_pb2.RemoteGrpc") -> None: - proto.Clear() - proto.host = ros_msg.host - proto.service_name = ros_msg.service_name - proto.timeout = ros_msg.timeout - del proto.lease_resources[:] - for _item in ros_msg.lease_resources: - proto.lease_resources.append(_item) - del proto.inputs[:] - for _item in ros_msg.inputs: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.inputs.add()) - proto.group_name_format = ros_msg.group_name_format - if ros_msg.params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_sleep(proto: "bosdyn.api.mission.nodes_pb2.Sleep", ros_msg: "bosdyn_msgs.msgs.Sleep") -> None: - ros_msg.seconds = proto.seconds - ros_msg.restart_after_stop = proto.restart_after_stop - - -def convert_bosdyn_msgs_sleep_to_proto(ros_msg: "bosdyn_msgs.msgs.Sleep", proto: "bosdyn.api.mission.nodes_pb2.Sleep") -> None: - proto.Clear() - proto.seconds = ros_msg.seconds - proto.restart_after_stop = ros_msg.restart_after_stop - - -def convert_proto_to_bosdyn_msgs_prompt_option(proto: "bosdyn.api.mission.nodes_pb2.Prompt.Option", ros_msg: "bosdyn_msgs.msgs.PromptOption") -> None: - ros_msg.text = proto.text - ros_msg.answer_code = proto.answer_code - - -def convert_bosdyn_msgs_prompt_option_to_proto(ros_msg: "bosdyn_msgs.msgs.PromptOption", proto: "bosdyn.api.mission.nodes_pb2.Prompt.Option") -> None: - proto.Clear() - proto.text = ros_msg.text - proto.answer_code = ros_msg.answer_code - - -def convert_proto_to_bosdyn_msgs_prompt(proto: "bosdyn.api.mission.nodes_pb2.Prompt", ros_msg: "bosdyn_msgs.msgs.Prompt") -> None: - ros_msg.always_reprompt = proto.always_reprompt - ros_msg.text = proto.text - ros_msg.source = proto.source - from bosdyn_msgs.msg import PromptOption - ros_msg.options = [] - for _item in proto.options: - ros_msg.options.append(PromptOption()) - convert_proto_to_bosdyn_msgs_prompt_option(_item, ros_msg.options[-1]) - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.for_autonomous_processing = proto.for_autonomous_processing - ros_msg.severity.value = proto.severity - ros_msg.question_name_in_blackboard = proto.question_name_in_blackboard - - -def convert_bosdyn_msgs_prompt_to_proto(ros_msg: "bosdyn_msgs.msgs.Prompt", proto: "bosdyn.api.mission.nodes_pb2.Prompt") -> None: - proto.Clear() - proto.always_reprompt = ros_msg.always_reprompt - proto.text = ros_msg.text - proto.source = ros_msg.source - del proto.options[:] - for _item in ros_msg.options: - convert_bosdyn_msgs_prompt_option_to_proto(_item, proto.options.add()) - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.for_autonomous_processing = ros_msg.for_autonomous_processing - proto.severity = ros_msg.severity.value - proto.question_name_in_blackboard = ros_msg.question_name_in_blackboard - - -def convert_proto_to_bosdyn_msgs_bosdyn_gripper_camera_params_state(proto: "bosdyn.api.mission.nodes_pb2.BosdynGripperCameraParamsState", ros_msg: "bosdyn_msgs.msgs.BosdynGripperCameraParamsState") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - ros_msg.state_name = proto.state_name - - -def convert_bosdyn_msgs_bosdyn_gripper_camera_params_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BosdynGripperCameraParamsState", proto: "bosdyn.api.mission.nodes_pb2.BosdynGripperCameraParamsState") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - proto.state_name = ros_msg.state_name - - -def convert_proto_to_bosdyn_msgs_set_gripper_camera_params_one_of_params(proto: "bosdyn.api.mission.nodes_pb2.SetGripperCameraParams", ros_msg: "bosdyn_msgs.msgs.SetGripperCameraParamsOneOfParams") -> None: - if proto.HasField("params_in_blackboard_key"): - ros_msg.params_choice = ros_msg.PARAMS_PARAMS_IN_BLACKBOARD_KEY_SET - ros_msg.params_in_blackboard_key = proto.params_in_blackboard_key - if proto.HasField("new_params"): - ros_msg.params_choice = ros_msg.PARAMS_NEW_PARAMS_SET - convert_proto_to_bosdyn_msgs_gripper_camera_params(proto.new_params, ros_msg.new_params) - - -def convert_bosdyn_msgs_set_gripper_camera_params_one_of_params_to_proto(ros_msg: "bosdyn_msgs.msgs.SetGripperCameraParamsOneOfParams", proto: "bosdyn.api.mission.nodes_pb2.SetGripperCameraParams") -> None: - proto.ClearField("params") - if ros_msg.params_choice == ros_msg.PARAMS_PARAMS_IN_BLACKBOARD_KEY_SET: - proto.params_in_blackboard_key = ros_msg.params_in_blackboard_key - if ros_msg.params_choice == ros_msg.PARAMS_NEW_PARAMS_SET: - convert_bosdyn_msgs_gripper_camera_params_to_proto(ros_msg.new_params, proto.new_params) - - -def convert_proto_to_bosdyn_msgs_set_gripper_camera_params(proto: "bosdyn.api.mission.nodes_pb2.SetGripperCameraParams", ros_msg: "bosdyn_msgs.msgs.SetGripperCameraParams") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_set_gripper_camera_params_one_of_params(proto, ros_msg.params) - - -def convert_bosdyn_msgs_set_gripper_camera_params_to_proto(ros_msg: "bosdyn_msgs.msgs.SetGripperCameraParams", proto: "bosdyn.api.mission.nodes_pb2.SetGripperCameraParams") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - convert_bosdyn_msgs_set_gripper_camera_params_one_of_params_to_proto(ros_msg.params, proto) - - -def convert_proto_to_bosdyn_msgs_set_grasp_override(proto: "bosdyn.api.mission.nodes_pb2.SetGraspOverride", ros_msg: "bosdyn_msgs.msgs.SetGraspOverride") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_api_grasp_override_request(proto.grasp_override_request, ros_msg.grasp_override_request) - ros_msg.grasp_override_request_is_set = proto.HasField("grasp_override_request") - - -def convert_bosdyn_msgs_set_grasp_override_to_proto(ros_msg: "bosdyn_msgs.msgs.SetGraspOverride", proto: "bosdyn.api.mission.nodes_pb2.SetGraspOverride") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.grasp_override_request_is_set: - convert_bosdyn_msgs_api_grasp_override_request_to_proto(ros_msg.grasp_override_request, proto.grasp_override_request) - - -def convert_proto_to_bosdyn_msgs_spot_cam_ptz_adjust_parameters(proto: "bosdyn.api.mission.nodes_pb2.SpotCamPtz.AdjustParameters", ros_msg: "bosdyn_msgs.msgs.SpotCamPtzAdjustParameters") -> None: - ros_msg.localization_varname = proto.localization_varname - ros_msg.waypoint_id = proto.waypoint_id - convert_proto_to_geometry_msgs_pose(proto.waypoint_tform_body, ros_msg.waypoint_tform_body) - ros_msg.waypoint_tform_body_is_set = proto.HasField("waypoint_tform_body") - - -def convert_bosdyn_msgs_spot_cam_ptz_adjust_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCamPtzAdjustParameters", proto: "bosdyn.api.mission.nodes_pb2.SpotCamPtz.AdjustParameters") -> None: - proto.Clear() - proto.localization_varname = ros_msg.localization_varname - proto.waypoint_id = ros_msg.waypoint_id - if ros_msg.waypoint_tform_body_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.waypoint_tform_body, proto.waypoint_tform_body) - - -def convert_proto_to_bosdyn_msgs_spot_cam_ptz(proto: "bosdyn.api.mission.nodes_pb2.SpotCamPtz", ros_msg: "bosdyn_msgs.msgs.SpotCamPtz") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_ptz_position(proto.ptz_position, ros_msg.ptz_position) - ros_msg.ptz_position_is_set = proto.HasField("ptz_position") - convert_proto_to_bosdyn_msgs_spot_cam_ptz_adjust_parameters(proto.adjust_parameters, ros_msg.adjust_parameters) - ros_msg.adjust_parameters_is_set = proto.HasField("adjust_parameters") - - -def convert_bosdyn_msgs_spot_cam_ptz_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCamPtz", proto: "bosdyn.api.mission.nodes_pb2.SpotCamPtz") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.ptz_position_is_set: - convert_bosdyn_msgs_ptz_position_to_proto(ros_msg.ptz_position, proto.ptz_position) - if ros_msg.adjust_parameters_is_set: - convert_bosdyn_msgs_spot_cam_ptz_adjust_parameters_to_proto(ros_msg.adjust_parameters, proto.adjust_parameters) - - -def convert_proto_to_bosdyn_msgs_spot_cam_store_media(proto: "bosdyn.api.mission.nodes_pb2.SpotCamStoreMedia", ros_msg: "bosdyn_msgs.msgs.SpotCamStoreMedia") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_camera(proto.camera, ros_msg.camera) - ros_msg.camera_is_set = proto.HasField("camera") - ros_msg.type.value = proto.type - ros_msg.tag = proto.tag - - -def convert_bosdyn_msgs_spot_cam_store_media_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCamStoreMedia", proto: "bosdyn.api.mission.nodes_pb2.SpotCamStoreMedia") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.camera_is_set: - convert_bosdyn_msgs_camera_to_proto(ros_msg.camera, proto.camera) - proto.type = ros_msg.type.value - proto.tag = ros_msg.tag - - -def convert_proto_to_bosdyn_msgs_spot_cam_led(proto: "bosdyn.api.mission.nodes_pb2.SpotCamLed", ros_msg: "bosdyn_msgs.msgs.SpotCamLed") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - from bosdyn_msgs.msg import KeyInt32ValueFloat32 - ros_msg.brightnesses = [] - for _item in proto.brightnesses: - ros_msg.brightnesses.append(KeyInt32ValueFloat32()) - ros_msg.brightnesses[-1].key = _item - ros_msg.brightnesses[-1].value = proto.brightnesses[_item] - - -def convert_bosdyn_msgs_spot_cam_led_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCamLed", proto: "bosdyn.api.mission.nodes_pb2.SpotCamLed") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - for _item in ros_msg.brightnesses: - proto.brightnesses[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_spot_cam_reset_autofocus(proto: "bosdyn.api.mission.nodes_pb2.SpotCamResetAutofocus", ros_msg: "bosdyn_msgs.msgs.SpotCamResetAutofocus") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - - -def convert_bosdyn_msgs_spot_cam_reset_autofocus_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCamResetAutofocus", proto: "bosdyn.api.mission.nodes_pb2.SpotCamResetAutofocus") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - - -def convert_proto_to_bosdyn_msgs_store_metadata_one_of_data(proto: "bosdyn.api.mission.nodes_pb2.StoreMetadata", ros_msg: "bosdyn_msgs.msgs.StoreMetadataOneOfData") -> None: - if proto.HasField("metadata_name"): - ros_msg.data_choice = ros_msg.DATA_METADATA_NAME_SET - ros_msg.metadata_name = proto.metadata_name - - -def convert_bosdyn_msgs_store_metadata_one_of_data_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreMetadataOneOfData", proto: "bosdyn.api.mission.nodes_pb2.StoreMetadata") -> None: - proto.ClearField("data") - if ros_msg.data_choice == ros_msg.DATA_METADATA_NAME_SET: - proto.metadata_name = ros_msg.metadata_name - - -def convert_proto_to_bosdyn_msgs_store_metadata(proto: "bosdyn.api.mission.nodes_pb2.StoreMetadata", ros_msg: "bosdyn_msgs.msgs.StoreMetadata") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - ros_msg.acquire_data_request_name = proto.acquire_data_request_name - convert_proto_to_bosdyn_msgs_store_metadata_one_of_data(proto, ros_msg.data) - ros_msg.metadata_channel = proto.metadata_channel - - -def convert_bosdyn_msgs_store_metadata_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreMetadata", proto: "bosdyn.api.mission.nodes_pb2.StoreMetadata") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - proto.acquire_data_request_name = ros_msg.acquire_data_request_name - convert_bosdyn_msgs_store_metadata_one_of_data_to_proto(ros_msg.data, proto) - proto.metadata_channel = ros_msg.metadata_channel - - -def convert_proto_to_bosdyn_msgs_data_acquisition_completion_behavior(proto: "bosdyn.api.mission.nodes_pb2.DataAcquisition.CompletionBehavior", ros_msg: "bosdyn_msgs.msgs.DataAcquisitionCompletionBehavior") -> None: - pass - - -def convert_bosdyn_msgs_data_acquisition_completion_behavior_to_proto(ros_msg: "bosdyn_msgs.msgs.DataAcquisitionCompletionBehavior", proto: "bosdyn.api.mission.nodes_pb2.DataAcquisition.CompletionBehavior") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_data_acquisition(proto: "bosdyn.api.mission.nodes_pb2.DataAcquisition", ros_msg: "bosdyn_msgs.msgs.DataAcquisition") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - convert_proto_to_bosdyn_msgs_acquire_data_request(proto.request, ros_msg.request) - ros_msg.request_is_set = proto.HasField("request") - ros_msg.completion_behavior.value = proto.completion_behavior - ros_msg.group_name_format = proto.group_name_format - ros_msg.request_name_in_blackboard = proto.request_name_in_blackboard - ros_msg.metadata_name_in_blackboard = proto.metadata_name_in_blackboard - ros_msg.action_name_format = proto.action_name_format - ros_msg.disable_cancel_on_pause_or_stop = proto.disable_cancel_on_pause_or_stop - - -def convert_bosdyn_msgs_data_acquisition_to_proto(ros_msg: "bosdyn_msgs.msgs.DataAcquisition", proto: "bosdyn.api.mission.nodes_pb2.DataAcquisition") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - if ros_msg.request_is_set: - convert_bosdyn_msgs_acquire_data_request_to_proto(ros_msg.request, proto.request) - proto.completion_behavior = ros_msg.completion_behavior.value - proto.group_name_format = ros_msg.group_name_format - proto.request_name_in_blackboard = ros_msg.request_name_in_blackboard - proto.metadata_name_in_blackboard = ros_msg.metadata_name_in_blackboard - proto.action_name_format = ros_msg.action_name_format - proto.disable_cancel_on_pause_or_stop = ros_msg.disable_cancel_on_pause_or_stop - - -def convert_proto_to_bosdyn_msgs_retain_lease(proto: "bosdyn.api.mission.nodes_pb2.RetainLease", ros_msg: "bosdyn_msgs.msgs.RetainLease") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - - -def convert_bosdyn_msgs_retain_lease_to_proto(ros_msg: "bosdyn_msgs.msgs.RetainLease", proto: "bosdyn.api.mission.nodes_pb2.RetainLease") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - - -def convert_proto_to_bosdyn_msgs_define_blackboard(proto: "bosdyn.api.mission.nodes_pb2.DefineBlackboard", ros_msg: "bosdyn_msgs.msgs.DefineBlackboard") -> None: - from bosdyn_msgs.msg import KeyValue - ros_msg.blackboard_variables = [] - for _item in proto.blackboard_variables: - ros_msg.blackboard_variables.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.blackboard_variables[-1]) - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - - -def convert_bosdyn_msgs_define_blackboard_to_proto(ros_msg: "bosdyn_msgs.msgs.DefineBlackboard", proto: "bosdyn.api.mission.nodes_pb2.DefineBlackboard") -> None: - proto.Clear() - del proto.blackboard_variables[:] - for _item in ros_msg.blackboard_variables: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.blackboard_variables.add()) - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - - -def convert_proto_to_bosdyn_msgs_set_blackboard(proto: "bosdyn.api.mission.nodes_pb2.SetBlackboard", ros_msg: "bosdyn_msgs.msgs.SetBlackboard") -> None: - from bosdyn_msgs.msg import KeyValue - ros_msg.blackboard_variables = [] - for _item in proto.blackboard_variables: - ros_msg.blackboard_variables.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.blackboard_variables[-1]) - - -def convert_bosdyn_msgs_set_blackboard_to_proto(ros_msg: "bosdyn_msgs.msgs.SetBlackboard", proto: "bosdyn.api.mission.nodes_pb2.SetBlackboard") -> None: - proto.Clear() - del proto.blackboard_variables[:] - for _item in ros_msg.blackboard_variables: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.blackboard_variables.add()) - - -def convert_proto_to_bosdyn_msgs_format_blackboard(proto: "bosdyn.api.mission.nodes_pb2.FormatBlackboard", ros_msg: "bosdyn_msgs.msgs.FormatBlackboard") -> None: - ros_msg.key = proto.key - ros_msg.format = proto.format - - -def convert_bosdyn_msgs_format_blackboard_to_proto(ros_msg: "bosdyn_msgs.msgs.FormatBlackboard", proto: "bosdyn.api.mission.nodes_pb2.FormatBlackboard") -> None: - proto.Clear() - proto.key = ros_msg.key - proto.format = ros_msg.format - - -def convert_proto_to_bosdyn_msgs_date_to_blackboard(proto: "bosdyn.api.mission.nodes_pb2.DateToBlackboard", ros_msg: "bosdyn_msgs.msgs.DateToBlackboard") -> None: - ros_msg.key = proto.key - - -def convert_bosdyn_msgs_date_to_blackboard_to_proto(ros_msg: "bosdyn_msgs.msgs.DateToBlackboard", proto: "bosdyn.api.mission.nodes_pb2.DateToBlackboard") -> None: - proto.Clear() - proto.key = ros_msg.key - - -def convert_proto_to_bosdyn_msgs_constant_result(proto: "bosdyn.api.mission.nodes_pb2.ConstantResult", ros_msg: "bosdyn_msgs.msgs.ConstantResult") -> None: - ros_msg.result.value = proto.result - - -def convert_bosdyn_msgs_constant_result_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstantResult", proto: "bosdyn.api.mission.nodes_pb2.ConstantResult") -> None: - proto.Clear() - proto.result = ros_msg.result.value - - -def convert_proto_to_bosdyn_msgs_restart_when_paused(proto: "bosdyn.api.mission.nodes_pb2.RestartWhenPaused", ros_msg: "bosdyn_msgs.msgs.RestartWhenPaused") -> None: - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - - -def convert_bosdyn_msgs_restart_when_paused_to_proto(ros_msg: "bosdyn_msgs.msgs.RestartWhenPaused", proto: "bosdyn.api.mission.nodes_pb2.RestartWhenPaused") -> None: - proto.Clear() - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - - -def convert_proto_to_bosdyn_msgs_data_acquisition_on_interruption(proto: "bosdyn.api.mission.nodes_pb2.DataAcquisitionOnInterruption", ros_msg: "bosdyn_msgs.msgs.DataAcquisitionOnInterruption") -> None: - convert_proto_to_bosdyn_msgs_node(proto.child, ros_msg.child) - ros_msg.child_is_set = proto.HasField("child") - convert_proto_to_bosdyn_msgs_data_acquisition(proto.request_when_interrupted, ros_msg.request_when_interrupted) - ros_msg.request_when_interrupted_is_set = proto.HasField("request_when_interrupted") - convert_proto_to_bosdyn_msgs_metadata(proto.pause_mission_metadata, ros_msg.pause_mission_metadata) - ros_msg.pause_mission_metadata_is_set = proto.HasField("pause_mission_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.restart_mission_metadata, ros_msg.restart_mission_metadata) - ros_msg.restart_mission_metadata_is_set = proto.HasField("restart_mission_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.load_mission_metadata, ros_msg.load_mission_metadata) - ros_msg.load_mission_metadata_is_set = proto.HasField("load_mission_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.stop_mission_metadata, ros_msg.stop_mission_metadata) - ros_msg.stop_mission_metadata_is_set = proto.HasField("stop_mission_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.lease_use_error_metadata, ros_msg.lease_use_error_metadata) - ros_msg.lease_use_error_metadata_is_set = proto.HasField("lease_use_error_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.play_mission_timeout_metadata, ros_msg.play_mission_timeout_metadata) - ros_msg.play_mission_timeout_metadata_is_set = proto.HasField("play_mission_timeout_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.child_node_error_metadata, ros_msg.child_node_error_metadata) - ros_msg.child_node_error_metadata_is_set = proto.HasField("child_node_error_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.child_node_exception_metadata, ros_msg.child_node_exception_metadata) - ros_msg.child_node_exception_metadata_is_set = proto.HasField("child_node_exception_metadata") - convert_proto_to_bosdyn_msgs_metadata(proto.default_metadata, ros_msg.default_metadata) - ros_msg.default_metadata_is_set = proto.HasField("default_metadata") - ros_msg.keys_for_lease_use_error_message = [] - for _item in proto.keys_for_lease_use_error_message: - ros_msg.keys_for_lease_use_error_message.append(_item) - - -def convert_bosdyn_msgs_data_acquisition_on_interruption_to_proto(ros_msg: "bosdyn_msgs.msgs.DataAcquisitionOnInterruption", proto: "bosdyn.api.mission.nodes_pb2.DataAcquisitionOnInterruption") -> None: - proto.Clear() - if ros_msg.child_is_set: - convert_bosdyn_msgs_node_to_proto(ros_msg.child, proto.child) - if ros_msg.request_when_interrupted_is_set: - convert_bosdyn_msgs_data_acquisition_to_proto(ros_msg.request_when_interrupted, proto.request_when_interrupted) - if ros_msg.pause_mission_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.pause_mission_metadata, proto.pause_mission_metadata) - if ros_msg.restart_mission_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.restart_mission_metadata, proto.restart_mission_metadata) - if ros_msg.load_mission_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.load_mission_metadata, proto.load_mission_metadata) - if ros_msg.stop_mission_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.stop_mission_metadata, proto.stop_mission_metadata) - if ros_msg.lease_use_error_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.lease_use_error_metadata, proto.lease_use_error_metadata) - if ros_msg.play_mission_timeout_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.play_mission_timeout_metadata, proto.play_mission_timeout_metadata) - if ros_msg.child_node_error_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.child_node_error_metadata, proto.child_node_error_metadata) - if ros_msg.child_node_exception_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.child_node_exception_metadata, proto.child_node_exception_metadata) - if ros_msg.default_metadata_is_set: - convert_bosdyn_msgs_metadata_to_proto(ros_msg.default_metadata, proto.default_metadata) - del proto.keys_for_lease_use_error_message[:] - for _item in ros_msg.keys_for_lease_use_error_message: - proto.keys_for_lease_use_error_message.append(_item) - - -def convert_proto_to_bosdyn_msgs_clear_behavior_faults(proto: "bosdyn.api.mission.nodes_pb2.ClearBehaviorFaults", ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaults") -> None: - ros_msg.service_name = proto.service_name - ros_msg.host = proto.host - ros_msg.robot_state_blackboard_name = proto.robot_state_blackboard_name - ros_msg.cleared_cause_fall_blackboard_name = proto.cleared_cause_fall_blackboard_name - ros_msg.cleared_cause_hardware_blackboard_name = proto.cleared_cause_hardware_blackboard_name - ros_msg.cleared_cause_lease_timeout_blackboard_name = proto.cleared_cause_lease_timeout_blackboard_name - - -def convert_bosdyn_msgs_clear_behavior_faults_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaults", proto: "bosdyn.api.mission.nodes_pb2.ClearBehaviorFaults") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - proto.host = ros_msg.host - proto.robot_state_blackboard_name = ros_msg.robot_state_blackboard_name - proto.cleared_cause_fall_blackboard_name = ros_msg.cleared_cause_fall_blackboard_name - proto.cleared_cause_hardware_blackboard_name = ros_msg.cleared_cause_hardware_blackboard_name - proto.cleared_cause_lease_timeout_blackboard_name = ros_msg.cleared_cause_lease_timeout_blackboard_name - - -def convert_proto_to_bosdyn_msgs_establish_session_request(proto: "bosdyn.api.mission.remote_pb2.EstablishSessionRequest", ros_msg: "bosdyn_msgs.msgs.EstablishSessionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - - -def convert_bosdyn_msgs_establish_session_request_to_proto(ros_msg: "bosdyn_msgs.msgs.EstablishSessionRequest", proto: "bosdyn.api.mission.remote_pb2.EstablishSessionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - - -def convert_proto_to_bosdyn_msgs_establish_session_response_status(proto: "bosdyn.api.mission.remote_pb2.EstablishSessionResponse.Status", ros_msg: "bosdyn_msgs.msgs.EstablishSessionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_establish_session_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.EstablishSessionResponseStatus", proto: "bosdyn.api.mission.remote_pb2.EstablishSessionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_establish_session_response(proto: "bosdyn.api.mission.remote_pb2.EstablishSessionResponse", ros_msg: "bosdyn_msgs.msgs.EstablishSessionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.session_id = proto.session_id - ros_msg.missing_lease_resources = [] - for _item in proto.missing_lease_resources: - ros_msg.missing_lease_resources.append(_item) - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - - -def convert_bosdyn_msgs_establish_session_response_to_proto(ros_msg: "bosdyn_msgs.msgs.EstablishSessionResponse", proto: "bosdyn.api.mission.remote_pb2.EstablishSessionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.session_id = ros_msg.session_id - del proto.missing_lease_resources[:] - for _item in ros_msg.missing_lease_resources: - proto.missing_lease_resources.append(_item) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - - -def convert_proto_to_bosdyn_msgs_tick_request(proto: "bosdyn.api.mission.remote_pb2.TickRequest", ros_msg: "bosdyn_msgs.msgs.TickRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.session_id = proto.session_id - from bosdyn_msgs.msg import Lease - ros_msg.leases = [] - for _item in proto.leases: - ros_msg.leases.append(Lease()) - convert_proto_to_bosdyn_msgs_lease(_item, ros_msg.leases[-1]) - from bosdyn_msgs.msg import KeyValue - ros_msg.inputs = [] - for _item in proto.inputs: - ros_msg.inputs.append(KeyValue()) - convert_proto_to_bosdyn_msgs_key_value(_item, ros_msg.inputs[-1]) - convert_proto_to_bosdyn_msgs_dict_param(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - ros_msg.group_name = proto.group_name - - -def convert_bosdyn_msgs_tick_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TickRequest", proto: "bosdyn.api.mission.remote_pb2.TickRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.session_id = ros_msg.session_id - del proto.leases[:] - for _item in ros_msg.leases: - convert_bosdyn_msgs_lease_to_proto(_item, proto.leases.add()) - del proto.inputs[:] - for _item in ros_msg.inputs: - convert_bosdyn_msgs_key_value_to_proto(_item, proto.inputs.add()) - if ros_msg.params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.params, proto.params) - proto.group_name = ros_msg.group_name - - -def convert_proto_to_bosdyn_msgs_tick_response_status(proto: "bosdyn.api.mission.remote_pb2.TickResponse.Status", ros_msg: "bosdyn_msgs.msgs.TickResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_tick_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TickResponseStatus", proto: "bosdyn.api.mission.remote_pb2.TickResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_tick_response(proto: "bosdyn.api.mission.remote_pb2.TickResponse", ros_msg: "bosdyn_msgs.msgs.TickResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.missing_lease_resources = [] - for _item in proto.missing_lease_resources: - ros_msg.missing_lease_resources.append(_item) - from bosdyn_msgs.msg import LeaseUseResult - ros_msg.lease_use_results = [] - for _item in proto.lease_use_results: - ros_msg.lease_use_results.append(LeaseUseResult()) - convert_proto_to_bosdyn_msgs_lease_use_result(_item, ros_msg.lease_use_results[-1]) - from bosdyn_msgs.msg import VariableDeclaration - ros_msg.missing_inputs = [] - for _item in proto.missing_inputs: - ros_msg.missing_inputs.append(VariableDeclaration()) - convert_proto_to_bosdyn_msgs_variable_declaration(_item, ros_msg.missing_inputs[-1]) - ros_msg.error_message = proto.error_message - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - - -def convert_bosdyn_msgs_tick_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TickResponse", proto: "bosdyn.api.mission.remote_pb2.TickResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.missing_lease_resources[:] - for _item in ros_msg.missing_lease_resources: - proto.missing_lease_resources.append(_item) - del proto.lease_use_results[:] - for _item in ros_msg.lease_use_results: - convert_bosdyn_msgs_lease_use_result_to_proto(_item, proto.lease_use_results.add()) - del proto.missing_inputs[:] - for _item in ros_msg.missing_inputs: - convert_bosdyn_msgs_variable_declaration_to_proto(_item, proto.missing_inputs.add()) - proto.error_message = ros_msg.error_message - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - - -def convert_proto_to_bosdyn_msgs_stop_request(proto: "bosdyn.api.mission.remote_pb2.StopRequest", ros_msg: "bosdyn_msgs.msgs.StopRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.session_id = proto.session_id - - -def convert_bosdyn_msgs_stop_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StopRequest", proto: "bosdyn.api.mission.remote_pb2.StopRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.session_id = ros_msg.session_id - - -def convert_proto_to_bosdyn_msgs_stop_response_status(proto: "bosdyn.api.mission.remote_pb2.StopResponse.Status", ros_msg: "bosdyn_msgs.msgs.StopResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_stop_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.StopResponseStatus", proto: "bosdyn.api.mission.remote_pb2.StopResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stop_response(proto: "bosdyn.api.mission.remote_pb2.StopResponse", ros_msg: "bosdyn_msgs.msgs.StopResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_stop_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StopResponse", proto: "bosdyn.api.mission.remote_pb2.StopResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_teardown_session_request(proto: "bosdyn.api.mission.remote_pb2.TeardownSessionRequest", ros_msg: "bosdyn_msgs.msgs.TeardownSessionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.session_id = proto.session_id - - -def convert_bosdyn_msgs_teardown_session_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TeardownSessionRequest", proto: "bosdyn.api.mission.remote_pb2.TeardownSessionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.session_id = ros_msg.session_id - - -def convert_proto_to_bosdyn_msgs_teardown_session_response_status(proto: "bosdyn.api.mission.remote_pb2.TeardownSessionResponse.Status", ros_msg: "bosdyn_msgs.msgs.TeardownSessionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_teardown_session_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TeardownSessionResponseStatus", proto: "bosdyn.api.mission.remote_pb2.TeardownSessionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_teardown_session_response(proto: "bosdyn.api.mission.remote_pb2.TeardownSessionResponse", ros_msg: "bosdyn_msgs.msgs.TeardownSessionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_teardown_session_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TeardownSessionResponse", proto: "bosdyn.api.mission.remote_pb2.TeardownSessionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_get_remote_mission_service_info_request(proto: "bosdyn.api.mission.remote_pb2.GetRemoteMissionServiceInfoRequest", ros_msg: "bosdyn_msgs.msgs.GetRemoteMissionServiceInfoRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_remote_mission_service_info_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRemoteMissionServiceInfoRequest", proto: "bosdyn.api.mission.remote_pb2.GetRemoteMissionServiceInfoRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_remote_mission_service_info_response(proto: "bosdyn.api.mission.remote_pb2.GetRemoteMissionServiceInfoResponse", ros_msg: "bosdyn_msgs.msgs.GetRemoteMissionServiceInfoResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_get_remote_mission_service_info_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetRemoteMissionServiceInfoResponse", proto: "bosdyn.api.mission.remote_pb2.GetRemoteMissionServiceInfoResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_key_value(proto: "bosdyn.api.mission.util_pb2.KeyValue", ros_msg: "bosdyn_msgs.msgs.KeyValue") -> None: - ros_msg.key = proto.key - convert_proto_to_bosdyn_msgs_value(proto.value, ros_msg.value) - ros_msg.value_is_set = proto.HasField("value") - - -def convert_bosdyn_msgs_key_value_to_proto(ros_msg: "bosdyn_msgs.msgs.KeyValue", proto: "bosdyn.api.mission.util_pb2.KeyValue") -> None: - proto.Clear() - proto.key = ros_msg.key - if ros_msg.value_is_set: - convert_bosdyn_msgs_value_to_proto(ros_msg.value, proto.value) - - -def convert_proto_to_bosdyn_msgs_value_one_of_source(proto: "bosdyn.api.mission.util_pb2.Value", ros_msg: "bosdyn_msgs.msgs.ValueOneOfSource") -> None: - if proto.HasField("constant"): - ros_msg.source_choice = ros_msg.SOURCE_CONSTANT_SET - convert_proto_to_bosdyn_msgs_constant_value(proto.constant, ros_msg.constant) - if proto.HasField("runtime_var"): - ros_msg.source_choice = ros_msg.SOURCE_RUNTIME_VAR_SET - convert_proto_to_bosdyn_msgs_variable_declaration(proto.runtime_var, ros_msg.runtime_var) - if proto.HasField("parameter"): - ros_msg.source_choice = ros_msg.SOURCE_PARAMETER_SET - convert_proto_to_bosdyn_msgs_variable_declaration(proto.parameter, ros_msg.parameter) - - -def convert_bosdyn_msgs_value_one_of_source_to_proto(ros_msg: "bosdyn_msgs.msgs.ValueOneOfSource", proto: "bosdyn.api.mission.util_pb2.Value") -> None: - proto.ClearField("source") - if ros_msg.source_choice == ros_msg.SOURCE_CONSTANT_SET: - convert_bosdyn_msgs_constant_value_to_proto(ros_msg.constant, proto.constant) - if ros_msg.source_choice == ros_msg.SOURCE_RUNTIME_VAR_SET: - convert_bosdyn_msgs_variable_declaration_to_proto(ros_msg.runtime_var, proto.runtime_var) - if ros_msg.source_choice == ros_msg.SOURCE_PARAMETER_SET: - convert_bosdyn_msgs_variable_declaration_to_proto(ros_msg.parameter, proto.parameter) - - -def convert_proto_to_bosdyn_msgs_value(proto: "bosdyn.api.mission.util_pb2.Value", ros_msg: "bosdyn_msgs.msgs.Value") -> None: - convert_proto_to_bosdyn_msgs_value_one_of_source(proto, ros_msg.source) - - -def convert_bosdyn_msgs_value_to_proto(ros_msg: "bosdyn_msgs.msgs.Value", proto: "bosdyn.api.mission.util_pb2.Value") -> None: - proto.Clear() - convert_bosdyn_msgs_value_one_of_source_to_proto(ros_msg.source, proto) - - -def convert_proto_to_bosdyn_msgs_variable_declaration_type(proto: "bosdyn.api.mission.util_pb2.VariableDeclaration.Type", ros_msg: "bosdyn_msgs.msgs.VariableDeclarationType") -> None: - pass - - -def convert_bosdyn_msgs_variable_declaration_type_to_proto(ros_msg: "bosdyn_msgs.msgs.VariableDeclarationType", proto: "bosdyn.api.mission.util_pb2.VariableDeclaration.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_variable_declaration(proto: "bosdyn.api.mission.util_pb2.VariableDeclaration", ros_msg: "bosdyn_msgs.msgs.VariableDeclaration") -> None: - ros_msg.name = proto.name - ros_msg.type.value = proto.type - - -def convert_bosdyn_msgs_variable_declaration_to_proto(ros_msg: "bosdyn_msgs.msgs.VariableDeclaration", proto: "bosdyn.api.mission.util_pb2.VariableDeclaration") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.type = ros_msg.type.value - - -def convert_proto_to_bosdyn_msgs_constant_value_one_of_value(proto: "bosdyn.api.mission.util_pb2.ConstantValue", ros_msg: "bosdyn_msgs.msgs.ConstantValueOneOfValue") -> None: - if proto.HasField("float_value"): - ros_msg.value_choice = ros_msg.VALUE_FLOAT_VALUE_SET - ros_msg.float_value = proto.float_value - if proto.HasField("string_value"): - ros_msg.value_choice = ros_msg.VALUE_STRING_VALUE_SET - ros_msg.string_value = proto.string_value - if proto.HasField("int_value"): - ros_msg.value_choice = ros_msg.VALUE_INT_VALUE_SET - ros_msg.int_value = proto.int_value - if proto.HasField("bool_value"): - ros_msg.value_choice = ros_msg.VALUE_BOOL_VALUE_SET - ros_msg.bool_value = proto.bool_value - - -def convert_bosdyn_msgs_constant_value_one_of_value_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstantValueOneOfValue", proto: "bosdyn.api.mission.util_pb2.ConstantValue") -> None: - proto.ClearField("value") - if ros_msg.value_choice == ros_msg.VALUE_FLOAT_VALUE_SET: - proto.float_value = ros_msg.float_value - if ros_msg.value_choice == ros_msg.VALUE_STRING_VALUE_SET: - proto.string_value = ros_msg.string_value - if ros_msg.value_choice == ros_msg.VALUE_INT_VALUE_SET: - proto.int_value = ros_msg.int_value - if ros_msg.value_choice == ros_msg.VALUE_BOOL_VALUE_SET: - proto.bool_value = ros_msg.bool_value - - -def convert_proto_to_bosdyn_msgs_constant_value(proto: "bosdyn.api.mission.util_pb2.ConstantValue", ros_msg: "bosdyn_msgs.msgs.ConstantValue") -> None: - convert_proto_to_bosdyn_msgs_constant_value_one_of_value(proto, ros_msg.value) - - -def convert_bosdyn_msgs_constant_value_to_proto(ros_msg: "bosdyn_msgs.msgs.ConstantValue", proto: "bosdyn.api.mission.util_pb2.ConstantValue") -> None: - proto.Clear() - convert_bosdyn_msgs_constant_value_one_of_value_to_proto(ros_msg.value, proto) - - -def convert_proto_to_bosdyn_msgs_user_data(proto: "bosdyn.api.mission.util_pb2.UserData", ros_msg: "bosdyn_msgs.msgs.UserData") -> None: - ros_msg.id = proto.id - ros_msg.bytestring = proto.bytestring - - -def convert_bosdyn_msgs_user_data_to_proto(ros_msg: "bosdyn_msgs.msgs.UserData", proto: "bosdyn.api.mission.util_pb2.UserData") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.bytestring = ros_msg.bytestring - - -def convert_proto_to_bosdyn_msgs_result(proto: "bosdyn.api.mission.util_pb2.Result", ros_msg: "bosdyn_msgs.msgs.Result") -> None: - pass - - -def convert_bosdyn_msgs_result_to_proto(ros_msg: "bosdyn_msgs.msgs.Result", proto: "bosdyn.api.mission.util_pb2.Result") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_mobility_command_request_one_of_command(proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Request", ros_msg: "bosdyn_msgs.msgs.MobilityCommandRequestOneOfCommand") -> None: - if proto.HasField("se2_trajectory_request"): - ros_msg.command_choice = ros_msg.COMMAND_SE2_TRAJECTORY_REQUEST_SET - convert_proto_to_bosdyn_msgs_se2_trajectory_command_request(proto.se2_trajectory_request, ros_msg.se2_trajectory_request) - if proto.HasField("se2_velocity_request"): - ros_msg.command_choice = ros_msg.COMMAND_SE2_VELOCITY_REQUEST_SET - convert_proto_to_bosdyn_msgs_se2_velocity_command_request(proto.se2_velocity_request, ros_msg.se2_velocity_request) - if proto.HasField("sit_request"): - ros_msg.command_choice = ros_msg.COMMAND_SIT_REQUEST_SET - convert_proto_to_bosdyn_msgs_sit_command_request(proto.sit_request, ros_msg.sit_request) - if proto.HasField("stand_request"): - ros_msg.command_choice = ros_msg.COMMAND_STAND_REQUEST_SET - convert_proto_to_bosdyn_msgs_stand_command_request(proto.stand_request, ros_msg.stand_request) - if proto.HasField("stance_request"): - ros_msg.command_choice = ros_msg.COMMAND_STANCE_REQUEST_SET - convert_proto_to_bosdyn_msgs_stance_command_request(proto.stance_request, ros_msg.stance_request) - if proto.HasField("stop_request"): - ros_msg.command_choice = ros_msg.COMMAND_STOP_REQUEST_SET - convert_proto_to_bosdyn_msgs_stop_command_request(proto.stop_request, ros_msg.stop_request) - if proto.HasField("follow_arm_request"): - ros_msg.command_choice = ros_msg.COMMAND_FOLLOW_ARM_REQUEST_SET - convert_proto_to_bosdyn_msgs_follow_arm_command_request(proto.follow_arm_request, ros_msg.follow_arm_request) - - -def convert_bosdyn_msgs_mobility_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityCommandRequestOneOfCommand", proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_SE2_TRAJECTORY_REQUEST_SET: - convert_bosdyn_msgs_se2_trajectory_command_request_to_proto(ros_msg.se2_trajectory_request, proto.se2_trajectory_request) - if ros_msg.command_choice == ros_msg.COMMAND_SE2_VELOCITY_REQUEST_SET: - convert_bosdyn_msgs_se2_velocity_command_request_to_proto(ros_msg.se2_velocity_request, proto.se2_velocity_request) - if ros_msg.command_choice == ros_msg.COMMAND_SIT_REQUEST_SET: - convert_bosdyn_msgs_sit_command_request_to_proto(ros_msg.sit_request, proto.sit_request) - if ros_msg.command_choice == ros_msg.COMMAND_STAND_REQUEST_SET: - convert_bosdyn_msgs_stand_command_request_to_proto(ros_msg.stand_request, proto.stand_request) - if ros_msg.command_choice == ros_msg.COMMAND_STANCE_REQUEST_SET: - convert_bosdyn_msgs_stance_command_request_to_proto(ros_msg.stance_request, proto.stance_request) - if ros_msg.command_choice == ros_msg.COMMAND_STOP_REQUEST_SET: - convert_bosdyn_msgs_stop_command_request_to_proto(ros_msg.stop_request, proto.stop_request) - if ros_msg.command_choice == ros_msg.COMMAND_FOLLOW_ARM_REQUEST_SET: - convert_bosdyn_msgs_follow_arm_command_request_to_proto(ros_msg.follow_arm_request, proto.follow_arm_request) - - -def convert_proto_to_bosdyn_msgs_mobility_command_request(proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Request", ros_msg: "bosdyn_msgs.msgs.MobilityCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_mobility_command_request_one_of_command(proto, ros_msg.command) - convert_any_proto_to_bosdyn_msgs_mobility_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_mobility_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityCommandRequest", proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_mobility_command_request_one_of_command_to_proto(ros_msg.command, proto) - if ros_msg.params_is_set: - convert_bosdyn_msgs_mobility_params_to_any_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_mobility_command_feedback_one_of_feedback(proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.MobilityCommandFeedbackOneOfFeedback") -> None: - if proto.HasField("se2_trajectory_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_SE2_TRAJECTORY_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_se2_trajectory_command_feedback(proto.se2_trajectory_feedback, ros_msg.se2_trajectory_feedback) - if proto.HasField("se2_velocity_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_SE2_VELOCITY_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_se2_velocity_command_feedback(proto.se2_velocity_feedback, ros_msg.se2_velocity_feedback) - if proto.HasField("sit_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_SIT_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_sit_command_feedback(proto.sit_feedback, ros_msg.sit_feedback) - if proto.HasField("stand_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_STAND_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_stand_command_feedback(proto.stand_feedback, ros_msg.stand_feedback) - if proto.HasField("stance_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_STANCE_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_stance_command_feedback(proto.stance_feedback, ros_msg.stance_feedback) - if proto.HasField("stop_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_STOP_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_stop_command_feedback(proto.stop_feedback, ros_msg.stop_feedback) - if proto.HasField("follow_arm_feedback"): - ros_msg.feedback_choice = ros_msg.FEEDBACK_FOLLOW_ARM_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_follow_arm_command_feedback(proto.follow_arm_feedback, ros_msg.follow_arm_feedback) - - -def convert_bosdyn_msgs_mobility_command_feedback_one_of_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityCommandFeedbackOneOfFeedback", proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Feedback") -> None: - proto.ClearField("feedback") - if ros_msg.feedback_choice == ros_msg.FEEDBACK_SE2_TRAJECTORY_FEEDBACK_SET: - convert_bosdyn_msgs_se2_trajectory_command_feedback_to_proto(ros_msg.se2_trajectory_feedback, proto.se2_trajectory_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_SE2_VELOCITY_FEEDBACK_SET: - convert_bosdyn_msgs_se2_velocity_command_feedback_to_proto(ros_msg.se2_velocity_feedback, proto.se2_velocity_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_SIT_FEEDBACK_SET: - convert_bosdyn_msgs_sit_command_feedback_to_proto(ros_msg.sit_feedback, proto.sit_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_STAND_FEEDBACK_SET: - convert_bosdyn_msgs_stand_command_feedback_to_proto(ros_msg.stand_feedback, proto.stand_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_STANCE_FEEDBACK_SET: - convert_bosdyn_msgs_stance_command_feedback_to_proto(ros_msg.stance_feedback, proto.stance_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_STOP_FEEDBACK_SET: - convert_bosdyn_msgs_stop_command_feedback_to_proto(ros_msg.stop_feedback, proto.stop_feedback) - if ros_msg.feedback_choice == ros_msg.FEEDBACK_FOLLOW_ARM_FEEDBACK_SET: - convert_bosdyn_msgs_follow_arm_command_feedback_to_proto(ros_msg.follow_arm_feedback, proto.follow_arm_feedback) - - -def convert_proto_to_bosdyn_msgs_mobility_command_feedback(proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.MobilityCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_mobility_command_feedback_one_of_feedback(proto, ros_msg.feedback) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_mobility_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityCommandFeedback", proto: "bosdyn.api.mobility_command_pb2.MobilityCommand.Feedback") -> None: - proto.Clear() - convert_bosdyn_msgs_mobility_command_feedback_one_of_feedback_to_proto(ros_msg.feedback, proto) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_mobility_command(proto: "bosdyn.api.mobility_command_pb2.MobilityCommand", ros_msg: "bosdyn_msgs.msgs.MobilityCommand") -> None: - pass - - -def convert_bosdyn_msgs_mobility_command_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityCommand", proto: "bosdyn.api.mobility_command_pb2.MobilityCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_list_available_models_request(proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsRequest", ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_network_compute_server_configuration(proto.server_config, ros_msg.server_config) - ros_msg.server_config_is_set = proto.HasField("server_config") - - -def convert_bosdyn_msgs_list_available_models_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsRequest", proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.server_config_is_set: - convert_bosdyn_msgs_network_compute_server_configuration_to_proto(ros_msg.server_config, proto.server_config) - - -def convert_proto_to_bosdyn_msgs_list_available_models_response(proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsResponse", ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_available_models(proto.models, ros_msg.models) - ros_msg.models_is_set = proto.HasField("models") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_list_available_models_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsResponse", proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.models_is_set: - convert_bosdyn_msgs_available_models_to_proto(ros_msg.models, proto.models) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_available_models(proto: "bosdyn.api.network_compute_bridge_pb2.AvailableModels", ros_msg: "bosdyn_msgs.msgs.AvailableModels") -> None: - from bosdyn_msgs.msg import ModelData - ros_msg.data = [] - for _item in proto.data: - ros_msg.data.append(ModelData()) - convert_proto_to_bosdyn_msgs_model_data(_item, ros_msg.data[-1]) - - -def convert_bosdyn_msgs_available_models_to_proto(ros_msg: "bosdyn_msgs.msgs.AvailableModels", proto: "bosdyn.api.network_compute_bridge_pb2.AvailableModels") -> None: - proto.Clear() - del proto.data[:] - for _item in ros_msg.data: - convert_bosdyn_msgs_model_data_to_proto(_item, proto.data.add()) - - -def convert_proto_to_bosdyn_msgs_model_data(proto: "bosdyn.api.network_compute_bridge_pb2.ModelData", ros_msg: "bosdyn_msgs.msgs.ModelData") -> None: - ros_msg.model_name = proto.model_name - ros_msg.available_labels = [] - for _item in proto.available_labels: - ros_msg.available_labels.append(_item) - from bosdyn_msgs.msg import OutputImageSpec - ros_msg.output_image_spec = [] - for _item in proto.output_image_spec: - ros_msg.output_image_spec.append(OutputImageSpec()) - convert_proto_to_bosdyn_msgs_output_image_spec(_item, ros_msg.output_image_spec[-1]) - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_model_data_to_proto(ros_msg: "bosdyn_msgs.msgs.ModelData", proto: "bosdyn.api.network_compute_bridge_pb2.ModelData") -> None: - proto.Clear() - proto.model_name = ros_msg.model_name - del proto.available_labels[:] - for _item in ros_msg.available_labels: - proto.available_labels.append(_item) - del proto.output_image_spec[:] - for _item in ros_msg.output_image_spec: - convert_bosdyn_msgs_output_image_spec_to_proto(_item, proto.output_image_spec.add()) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_model_labels(proto: "bosdyn.api.network_compute_bridge_pb2.ModelLabels", ros_msg: "bosdyn_msgs.msgs.ModelLabels") -> None: - ros_msg.model_name = proto.model_name - ros_msg.available_labels = [] - for _item in proto.available_labels: - ros_msg.available_labels.append(_item) - - -def convert_bosdyn_msgs_model_labels_to_proto(ros_msg: "bosdyn_msgs.msgs.ModelLabels", proto: "bosdyn.api.network_compute_bridge_pb2.ModelLabels") -> None: - proto.Clear() - proto.model_name = ros_msg.model_name - del proto.available_labels[:] - for _item in ros_msg.available_labels: - proto.available_labels.append(_item) - - -def convert_proto_to_bosdyn_msgs_network_compute_request_one_of_input(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeRequest", ros_msg: "bosdyn_msgs.msgs.NetworkComputeRequestOneOfInput") -> None: - if proto.HasField("input_data_bridge"): - ros_msg.input_choice = ros_msg.INPUT_INPUT_DATA_BRIDGE_SET - convert_proto_to_bosdyn_msgs_network_compute_input_data_bridge(proto.input_data_bridge, ros_msg.input_data_bridge) - - -def convert_bosdyn_msgs_network_compute_request_one_of_input_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeRequestOneOfInput", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeRequest") -> None: - proto.ClearField("input") - if ros_msg.input_choice == ros_msg.INPUT_INPUT_DATA_BRIDGE_SET: - convert_bosdyn_msgs_network_compute_input_data_bridge_to_proto(ros_msg.input_data_bridge, proto.input_data_bridge) - - -def convert_proto_to_bosdyn_msgs_network_compute_request(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeRequest", ros_msg: "bosdyn_msgs.msgs.NetworkComputeRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_network_compute_request_one_of_input(proto, ros_msg.input) - convert_proto_to_bosdyn_msgs_network_compute_server_configuration(proto.server_config, ros_msg.server_config) - ros_msg.server_config_is_set = proto.HasField("server_config") - - -def convert_bosdyn_msgs_network_compute_request_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeRequest", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - convert_bosdyn_msgs_network_compute_request_one_of_input_to_proto(ros_msg.input, proto) - if ros_msg.server_config_is_set: - convert_bosdyn_msgs_network_compute_server_configuration_to_proto(ros_msg.server_config, proto.server_config) - - -def convert_proto_to_bosdyn_msgs_image_source_and_service_one_of_request_data(proto: "bosdyn.api.network_compute_bridge_pb2.ImageSourceAndService", ros_msg: "bosdyn_msgs.msgs.ImageSourceAndServiceOneOfRequestData") -> None: - if proto.HasField("image_source"): - ros_msg.request_data_choice = ros_msg.REQUEST_DATA_IMAGE_SOURCE_SET - ros_msg.image_source = proto.image_source - if proto.HasField("image_request"): - ros_msg.request_data_choice = ros_msg.REQUEST_DATA_IMAGE_REQUEST_SET - convert_proto_to_bosdyn_msgs_image_request(proto.image_request, ros_msg.image_request) - - -def convert_bosdyn_msgs_image_source_and_service_one_of_request_data_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourceAndServiceOneOfRequestData", proto: "bosdyn.api.network_compute_bridge_pb2.ImageSourceAndService") -> None: - proto.ClearField("request_data") - if ros_msg.request_data_choice == ros_msg.REQUEST_DATA_IMAGE_SOURCE_SET: - proto.image_source = ros_msg.image_source - if ros_msg.request_data_choice == ros_msg.REQUEST_DATA_IMAGE_REQUEST_SET: - convert_bosdyn_msgs_image_request_to_proto(ros_msg.image_request, proto.image_request) - - -def convert_proto_to_bosdyn_msgs_image_source_and_service(proto: "bosdyn.api.network_compute_bridge_pb2.ImageSourceAndService", ros_msg: "bosdyn_msgs.msgs.ImageSourceAndService") -> None: - convert_proto_to_bosdyn_msgs_image_source_and_service_one_of_request_data(proto, ros_msg.request_data) - ros_msg.image_service = proto.image_service - - -def convert_bosdyn_msgs_image_source_and_service_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageSourceAndService", proto: "bosdyn.api.network_compute_bridge_pb2.ImageSourceAndService") -> None: - proto.Clear() - convert_bosdyn_msgs_image_source_and_service_one_of_request_data_to_proto(ros_msg.request_data, proto) - proto.image_service = ros_msg.image_service - - -def convert_proto_to_bosdyn_msgs_output_data(proto: "bosdyn.api.network_compute_bridge_pb2.OutputData", ros_msg: "bosdyn_msgs.msgs.OutputData") -> None: - from bosdyn_msgs.msg import WorldObject - ros_msg.object_in_image = [] - for _item in proto.object_in_image: - ros_msg.object_in_image.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.object_in_image[-1]) - convert_proto_to_bosdyn_msgs_alert_data(proto.alert_data, ros_msg.alert_data) - ros_msg.alert_data_is_set = proto.HasField("alert_data") - - -def convert_bosdyn_msgs_output_data_to_proto(ros_msg: "bosdyn_msgs.msgs.OutputData", proto: "bosdyn.api.network_compute_bridge_pb2.OutputData") -> None: - proto.Clear() - del proto.object_in_image[:] - for _item in ros_msg.object_in_image: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.object_in_image.add()) - if ros_msg.alert_data_is_set: - convert_bosdyn_msgs_alert_data_to_proto(ros_msg.alert_data, proto.alert_data) - - -def convert_proto_to_bosdyn_msgs_compute_parameters(proto: "bosdyn.api.network_compute_bridge_pb2.ComputeParameters", ros_msg: "bosdyn_msgs.msgs.ComputeParameters") -> None: - ros_msg.model_name = proto.model_name - from bosdyn_msgs.msg import ImageCaptureAndSource - ros_msg.reference_images = [] - for _item in proto.reference_images: - ros_msg.reference_images.append(ImageCaptureAndSource()) - convert_proto_to_bosdyn_msgs_image_capture_and_source(_item, ros_msg.reference_images[-1]) - convert_proto_to_bosdyn_msgs_dict_param(proto.custom_params, ros_msg.custom_params) - ros_msg.custom_params_is_set = proto.HasField("custom_params") - - -def convert_bosdyn_msgs_compute_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.ComputeParameters", proto: "bosdyn.api.network_compute_bridge_pb2.ComputeParameters") -> None: - proto.Clear() - proto.model_name = ros_msg.model_name - del proto.reference_images[:] - for _item in ros_msg.reference_images: - convert_bosdyn_msgs_image_capture_and_source_to_proto(_item, proto.reference_images.add()) - if ros_msg.custom_params_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.custom_params, proto.custom_params) - - -def convert_proto_to_bosdyn_msgs_network_compute_input_data_bridge(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputDataBridge", ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataBridge") -> None: - from bosdyn_msgs.msg import ImageSourceAndService - ros_msg.image_sources_and_services = [] - for _item in proto.image_sources_and_services: - ros_msg.image_sources_and_services.append(ImageSourceAndService()) - convert_proto_to_bosdyn_msgs_image_source_and_service(_item, ros_msg.image_sources_and_services[-1]) - convert_proto_to_bosdyn_msgs_compute_parameters(proto.parameters, ros_msg.parameters) - ros_msg.parameters_is_set = proto.HasField("parameters") - - -def convert_bosdyn_msgs_network_compute_input_data_bridge_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataBridge", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputDataBridge") -> None: - proto.Clear() - del proto.image_sources_and_services[:] - for _item in ros_msg.image_sources_and_services: - convert_bosdyn_msgs_image_source_and_service_to_proto(_item, proto.image_sources_and_services.add()) - if ros_msg.parameters_is_set: - convert_bosdyn_msgs_compute_parameters_to_proto(ros_msg.parameters, proto.parameters) - - -def convert_proto_to_bosdyn_msgs_network_compute_input_data_worker(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputDataWorker", ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataWorker") -> None: - from bosdyn_msgs.msg import ImageCaptureAndSource - ros_msg.images = [] - for _item in proto.images: - ros_msg.images.append(ImageCaptureAndSource()) - convert_proto_to_bosdyn_msgs_image_capture_and_source(_item, ros_msg.images[-1]) - convert_proto_to_bosdyn_msgs_compute_parameters(proto.parameters, ros_msg.parameters) - ros_msg.parameters_is_set = proto.HasField("parameters") - - -def convert_bosdyn_msgs_network_compute_input_data_worker_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataWorker", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputDataWorker") -> None: - proto.Clear() - del proto.images[:] - for _item in ros_msg.images: - convert_bosdyn_msgs_image_capture_and_source_to_proto(_item, proto.images.add()) - if ros_msg.parameters_is_set: - convert_bosdyn_msgs_compute_parameters_to_proto(ros_msg.parameters, proto.parameters) - - -def convert_proto_to_bosdyn_msgs_network_compute_input_data_one_of_input(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData", ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataOneOfInput") -> None: - if proto.HasField("image_source_and_service"): - ros_msg.input_choice = ros_msg.INPUT_IMAGE_SOURCE_AND_SERVICE_SET - convert_proto_to_bosdyn_msgs_image_source_and_service(proto.image_source_and_service, ros_msg.image_source_and_service) - if proto.HasField("image"): - ros_msg.input_choice = ros_msg.INPUT_IMAGE_SET - convert_proto_to_bosdyn_msgs_image(proto.image, ros_msg.image) - - -def convert_bosdyn_msgs_network_compute_input_data_one_of_input_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataOneOfInput", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData") -> None: - proto.ClearField("input") - if ros_msg.input_choice == ros_msg.INPUT_IMAGE_SOURCE_AND_SERVICE_SET: - convert_bosdyn_msgs_image_source_and_service_to_proto(ros_msg.image_source_and_service, proto.image_source_and_service) - if ros_msg.input_choice == ros_msg.INPUT_IMAGE_SET: - convert_bosdyn_msgs_image_to_proto(ros_msg.image, proto.image) - - -def convert_proto_to_bosdyn_msgs_network_compute_input_data_rotate_image(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData.RotateImage", ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataRotateImage") -> None: - pass - - -def convert_bosdyn_msgs_network_compute_input_data_rotate_image_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputDataRotateImage", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData.RotateImage") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_network_compute_input_data(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData", ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputData") -> None: - convert_proto_to_bosdyn_msgs_network_compute_input_data_one_of_input(proto, ros_msg.input) - ros_msg.model_name = proto.model_name - ros_msg.min_confidence = proto.min_confidence - ros_msg.rotate_image.value = proto.rotate_image - - -def convert_bosdyn_msgs_network_compute_input_data_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeInputData", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeInputData") -> None: - proto.Clear() - convert_bosdyn_msgs_network_compute_input_data_one_of_input_to_proto(ros_msg.input, proto) - proto.model_name = ros_msg.model_name - proto.min_confidence = ros_msg.min_confidence - proto.rotate_image = ros_msg.rotate_image.value - - -def convert_proto_to_bosdyn_msgs_network_compute_server_configuration(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeServerConfiguration", ros_msg: "bosdyn_msgs.msgs.NetworkComputeServerConfiguration") -> None: - ros_msg.service_name = proto.service_name - - -def convert_bosdyn_msgs_network_compute_server_configuration_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeServerConfiguration", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeServerConfiguration") -> None: - proto.Clear() - proto.service_name = ros_msg.service_name - - -def convert_proto_to_bosdyn_msgs_output_image(proto: "bosdyn.api.network_compute_bridge_pb2.OutputImage", ros_msg: "bosdyn_msgs.msgs.OutputImage") -> None: - convert_proto_to_bosdyn_msgs_image_response(proto.image_response, ros_msg.image_response) - ros_msg.image_response_is_set = proto.HasField("image_response") - from bosdyn_msgs.msg import WorldObject - ros_msg.object_in_image = [] - for _item in proto.object_in_image: - ros_msg.object_in_image.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.object_in_image[-1]) - convert_proto_to_bosdyn_msgs_alert_data(proto.alert_data, ros_msg.alert_data) - ros_msg.alert_data_is_set = proto.HasField("alert_data") - - -def convert_bosdyn_msgs_output_image_to_proto(ros_msg: "bosdyn_msgs.msgs.OutputImage", proto: "bosdyn.api.network_compute_bridge_pb2.OutputImage") -> None: - proto.Clear() - if ros_msg.image_response_is_set: - convert_bosdyn_msgs_image_response_to_proto(ros_msg.image_response, proto.image_response) - del proto.object_in_image[:] - for _item in ros_msg.object_in_image: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.object_in_image.add()) - if ros_msg.alert_data_is_set: - convert_bosdyn_msgs_alert_data_to_proto(ros_msg.alert_data, proto.alert_data) - - -def convert_proto_to_bosdyn_msgs_output_image_spec(proto: "bosdyn.api.network_compute_bridge_pb2.OutputImageSpec", ros_msg: "bosdyn_msgs.msgs.OutputImageSpec") -> None: - ros_msg.key = proto.key - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_output_image_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.OutputImageSpec", proto: "bosdyn.api.network_compute_bridge_pb2.OutputImageSpec") -> None: - proto.Clear() - proto.key = ros_msg.key - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_network_compute_response(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeResponse", ros_msg: "bosdyn_msgs.msgs.NetworkComputeResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import WorldObject - ros_msg.object_in_image = [] - for _item in proto.object_in_image: - ros_msg.object_in_image.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.object_in_image[-1]) - from bosdyn_msgs.msg import ImageCaptureAndSource - ros_msg.image_responses = [] - for _item in proto.image_responses: - ros_msg.image_responses.append(ImageCaptureAndSource()) - convert_proto_to_bosdyn_msgs_image_capture_and_source(_item, ros_msg.image_responses[-1]) - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsOutputImage - ros_msg.output_images = [] - for _item in proto.output_images: - ros_msg.output_images.append(KeyStringValueBosdynMsgsOutputImage()) - ros_msg.output_images[-1].key = _item - convert_proto_to_bosdyn_msgs_output_image(proto.output_images[_item], ros_msg.output_images[-1].value) - - -def convert_bosdyn_msgs_network_compute_response_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeResponse", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.object_in_image[:] - for _item in ros_msg.object_in_image: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.object_in_image.add()) - del proto.image_responses[:] - for _item in ros_msg.image_responses: - convert_bosdyn_msgs_image_capture_and_source_to_proto(_item, proto.image_responses.add()) - proto.status = ros_msg.status.value - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - for _item in ros_msg.output_images: - convert_bosdyn_msgs_output_image_to_proto(_item.value, proto.output_images[_item.key]) - - -def convert_proto_to_bosdyn_msgs_worker_compute_request(proto: "bosdyn.api.network_compute_bridge_pb2.WorkerComputeRequest", ros_msg: "bosdyn_msgs.msgs.WorkerComputeRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_network_compute_input_data_worker(proto.input_data, ros_msg.input_data) - ros_msg.input_data_is_set = proto.HasField("input_data") - - -def convert_bosdyn_msgs_worker_compute_request_to_proto(ros_msg: "bosdyn_msgs.msgs.WorkerComputeRequest", proto: "bosdyn.api.network_compute_bridge_pb2.WorkerComputeRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.input_data_is_set: - convert_bosdyn_msgs_network_compute_input_data_worker_to_proto(ros_msg.input_data, proto.input_data) - - -def convert_proto_to_bosdyn_msgs_worker_compute_response(proto: "bosdyn.api.network_compute_bridge_pb2.WorkerComputeResponse", ros_msg: "bosdyn_msgs.msgs.WorkerComputeResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_custom_param_error(proto.custom_param_error, ros_msg.custom_param_error) - ros_msg.custom_param_error_is_set = proto.HasField("custom_param_error") - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsOutputImage - ros_msg.output_images = [] - for _item in proto.output_images: - ros_msg.output_images.append(KeyStringValueBosdynMsgsOutputImage()) - ros_msg.output_images[-1].key = _item - convert_proto_to_bosdyn_msgs_output_image(proto.output_images[_item], ros_msg.output_images[-1].value) - - -def convert_bosdyn_msgs_worker_compute_response_to_proto(ros_msg: "bosdyn_msgs.msgs.WorkerComputeResponse", proto: "bosdyn.api.network_compute_bridge_pb2.WorkerComputeResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.custom_param_error_is_set: - convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg.custom_param_error, proto.custom_param_error) - for _item in ros_msg.output_images: - convert_bosdyn_msgs_output_image_to_proto(_item.value, proto.output_images[_item.key]) - - -def convert_proto_to_bosdyn_msgs_network_compute_status(proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeStatus", ros_msg: "bosdyn_msgs.msgs.NetworkComputeStatus") -> None: - pass - - -def convert_bosdyn_msgs_network_compute_status_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkComputeStatus", proto: "bosdyn.api.network_compute_bridge_pb2.NetworkComputeStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_list_available_models_status(proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsStatus", ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsStatus") -> None: - pass - - -def convert_bosdyn_msgs_list_available_models_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ListAvailableModelsStatus", proto: "bosdyn.api.network_compute_bridge_pb2.ListAvailableModelsStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_association(proto: "bosdyn.api.network_stats_pb2.Association", ros_msg: "bosdyn_msgs.msgs.Association") -> None: - ros_msg.mac_address = proto.mac_address - convert_proto_to_builtin_interfaces_duration(proto.connected_time, ros_msg.connected_time) - ros_msg.connected_time_is_set = proto.HasField("connected_time") - ros_msg.rx_signal_dbm = proto.rx_signal_dbm - ros_msg.rx_signal_avg_dbm = proto.rx_signal_avg_dbm - ros_msg.rx_beacon_signal_avg_dbm = proto.rx_beacon_signal_avg_dbm - ros_msg.expected_bits_per_second = proto.expected_bits_per_second - ros_msg.rx_bytes = proto.rx_bytes - ros_msg.rx_packets = proto.rx_packets - ros_msg.rx_bits_per_second = proto.rx_bits_per_second - ros_msg.tx_bytes = proto.tx_bytes - ros_msg.tx_packets = proto.tx_packets - ros_msg.tx_bits_per_second = proto.tx_bits_per_second - ros_msg.tx_retries = proto.tx_retries - ros_msg.tx_failed = proto.tx_failed - ros_msg.beacons_received = proto.beacons_received - ros_msg.beacon_loss_count = proto.beacon_loss_count - - -def convert_bosdyn_msgs_association_to_proto(ros_msg: "bosdyn_msgs.msgs.Association", proto: "bosdyn.api.network_stats_pb2.Association") -> None: - proto.Clear() - proto.mac_address = ros_msg.mac_address - if ros_msg.connected_time_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.connected_time, proto.connected_time) - proto.rx_signal_dbm = ros_msg.rx_signal_dbm - proto.rx_signal_avg_dbm = ros_msg.rx_signal_avg_dbm - proto.rx_beacon_signal_avg_dbm = ros_msg.rx_beacon_signal_avg_dbm - proto.expected_bits_per_second = ros_msg.expected_bits_per_second - proto.rx_bytes = ros_msg.rx_bytes - proto.rx_packets = ros_msg.rx_packets - proto.rx_bits_per_second = ros_msg.rx_bits_per_second - proto.tx_bytes = ros_msg.tx_bytes - proto.tx_packets = ros_msg.tx_packets - proto.tx_bits_per_second = ros_msg.tx_bits_per_second - proto.tx_retries = ros_msg.tx_retries - proto.tx_failed = ros_msg.tx_failed - proto.beacons_received = ros_msg.beacons_received - proto.beacon_loss_count = ros_msg.beacon_loss_count - - -def convert_proto_to_bosdyn_msgs_wifi_device_type(proto: "bosdyn.api.network_stats_pb2.WifiDevice.Type", ros_msg: "bosdyn_msgs.msgs.WifiDeviceType") -> None: - pass - - -def convert_bosdyn_msgs_wifi_device_type_to_proto(ros_msg: "bosdyn_msgs.msgs.WifiDeviceType", proto: "bosdyn.api.network_stats_pb2.WifiDevice.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_wifi_device(proto: "bosdyn.api.network_stats_pb2.WifiDevice", ros_msg: "bosdyn_msgs.msgs.WifiDevice") -> None: - ros_msg.type.value = proto.type - ros_msg.name = proto.name - ros_msg.mac_address = proto.mac_address - ros_msg.ssid = proto.ssid - ros_msg.tx_power_dbm = proto.tx_power_dbm - from bosdyn_msgs.msg import Association - ros_msg.associations = [] - for _item in proto.associations: - ros_msg.associations.append(Association()) - convert_proto_to_bosdyn_msgs_association(_item, ros_msg.associations[-1]) - - -def convert_bosdyn_msgs_wifi_device_to_proto(ros_msg: "bosdyn_msgs.msgs.WifiDevice", proto: "bosdyn.api.network_stats_pb2.WifiDevice") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.name = ros_msg.name - proto.mac_address = ros_msg.mac_address - proto.ssid = ros_msg.ssid - proto.tx_power_dbm = ros_msg.tx_power_dbm - del proto.associations[:] - for _item in ros_msg.associations: - convert_bosdyn_msgs_association_to_proto(_item, proto.associations.add()) - - -def convert_proto_to_bosdyn_msgs_wifi_stats(proto: "bosdyn.api.network_stats_pb2.WifiStats", ros_msg: "bosdyn_msgs.msgs.WifiStats") -> None: - ros_msg.hostname = proto.hostname - from bosdyn_msgs.msg import WifiDevice - ros_msg.devices = [] - for _item in proto.devices: - ros_msg.devices.append(WifiDevice()) - convert_proto_to_bosdyn_msgs_wifi_device(_item, ros_msg.devices[-1]) - - -def convert_bosdyn_msgs_wifi_stats_to_proto(ros_msg: "bosdyn_msgs.msgs.WifiStats", proto: "bosdyn.api.network_stats_pb2.WifiStats") -> None: - proto.Clear() - proto.hostname = ros_msg.hostname - del proto.devices[:] - for _item in ros_msg.devices: - convert_bosdyn_msgs_wifi_device_to_proto(_item, proto.devices.add()) - - -def convert_proto_to_bosdyn_msgs_parameter_one_of_values(proto: "bosdyn.api.parameter_pb2.Parameter", ros_msg: "bosdyn_msgs.msgs.ParameterOneOfValues") -> None: - if proto.HasField("int_value"): - ros_msg.values_choice = ros_msg.VALUES_INT_VALUE_SET - ros_msg.int_value = proto.int_value - if proto.HasField("float_value"): - ros_msg.values_choice = ros_msg.VALUES_FLOAT_VALUE_SET - ros_msg.float_value = proto.float_value - if proto.HasField("timestamp"): - ros_msg.values_choice = ros_msg.VALUES_TIMESTAMP_SET - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - if proto.HasField("duration"): - ros_msg.values_choice = ros_msg.VALUES_DURATION_SET - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - if proto.HasField("string_value"): - ros_msg.values_choice = ros_msg.VALUES_STRING_VALUE_SET - ros_msg.string_value = proto.string_value - if proto.HasField("bool_value"): - ros_msg.values_choice = ros_msg.VALUES_BOOL_VALUE_SET - ros_msg.bool_value = proto.bool_value - if proto.HasField("uint_value"): - ros_msg.values_choice = ros_msg.VALUES_UINT_VALUE_SET - ros_msg.uint_value = proto.uint_value - - -def convert_bosdyn_msgs_parameter_one_of_values_to_proto(ros_msg: "bosdyn_msgs.msgs.ParameterOneOfValues", proto: "bosdyn.api.parameter_pb2.Parameter") -> None: - proto.ClearField("values") - if ros_msg.values_choice == ros_msg.VALUES_INT_VALUE_SET: - proto.int_value = ros_msg.int_value - if ros_msg.values_choice == ros_msg.VALUES_FLOAT_VALUE_SET: - proto.float_value = ros_msg.float_value - if ros_msg.values_choice == ros_msg.VALUES_TIMESTAMP_SET: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - if ros_msg.values_choice == ros_msg.VALUES_DURATION_SET: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - if ros_msg.values_choice == ros_msg.VALUES_STRING_VALUE_SET: - proto.string_value = ros_msg.string_value - if ros_msg.values_choice == ros_msg.VALUES_BOOL_VALUE_SET: - proto.bool_value = ros_msg.bool_value - if ros_msg.values_choice == ros_msg.VALUES_UINT_VALUE_SET: - proto.uint_value = ros_msg.uint_value - - -def convert_proto_to_bosdyn_msgs_parameter(proto: "bosdyn.api.parameter_pb2.Parameter", ros_msg: "bosdyn_msgs.msgs.Parameter") -> None: - ros_msg.label = proto.label - ros_msg.units = proto.units - convert_proto_to_bosdyn_msgs_parameter_one_of_values(proto, ros_msg.values) - ros_msg.notes = proto.notes - - -def convert_bosdyn_msgs_parameter_to_proto(ros_msg: "bosdyn_msgs.msgs.Parameter", proto: "bosdyn.api.parameter_pb2.Parameter") -> None: - proto.Clear() - proto.label = ros_msg.label - proto.units = ros_msg.units - convert_bosdyn_msgs_parameter_one_of_values_to_proto(ros_msg.values, proto) - proto.notes = ros_msg.notes - - -def convert_proto_to_bosdyn_msgs_payload(proto: "bosdyn.api.payload_pb2.Payload", ros_msg: "bosdyn_msgs.msgs.Payload") -> None: - ros_msg.guid = proto.GUID - ros_msg.name = proto.name - ros_msg.description = proto.description - ros_msg.label_prefix = [] - for _item in proto.label_prefix: - ros_msg.label_prefix.append(_item) - ros_msg.is_authorized = proto.is_authorized - ros_msg.is_enabled = proto.is_enabled - ros_msg.is_noncompute_payload = proto.is_noncompute_payload - convert_proto_to_bosdyn_msgs_software_version(proto.version, ros_msg.version) - ros_msg.version_is_set = proto.HasField("version") - convert_proto_to_geometry_msgs_pose(proto.body_tform_payload, ros_msg.body_tform_payload) - ros_msg.body_tform_payload_is_set = proto.HasField("body_tform_payload") - convert_proto_to_geometry_msgs_pose(proto.mount_tform_payload, ros_msg.mount_tform_payload) - ros_msg.mount_tform_payload_is_set = proto.HasField("mount_tform_payload") - ros_msg.mount_frame_name.value = proto.mount_frame_name - ros_msg.liveness_timeout_secs = proto.liveness_timeout_secs - ros_msg.ipv4_address = proto.ipv4_address - ros_msg.link_speed = proto.link_speed - convert_proto_to_bosdyn_msgs_payload_mass_volume_properties(proto.mass_volume_properties, ros_msg.mass_volume_properties) - ros_msg.mass_volume_properties_is_set = proto.HasField("mass_volume_properties") - from bosdyn_msgs.msg import PayloadPreset - ros_msg.preset_configurations = [] - for _item in proto.preset_configurations: - ros_msg.preset_configurations.append(PayloadPreset()) - convert_proto_to_bosdyn_msgs_payload_preset(_item, ros_msg.preset_configurations[-1]) - - -def convert_bosdyn_msgs_payload_to_proto(ros_msg: "bosdyn_msgs.msgs.Payload", proto: "bosdyn.api.payload_pb2.Payload") -> None: - proto.Clear() - proto.GUID = ros_msg.guid - proto.name = ros_msg.name - proto.description = ros_msg.description - del proto.label_prefix[:] - for _item in ros_msg.label_prefix: - proto.label_prefix.append(_item) - proto.is_authorized = ros_msg.is_authorized - proto.is_enabled = ros_msg.is_enabled - proto.is_noncompute_payload = ros_msg.is_noncompute_payload - if ros_msg.version_is_set: - convert_bosdyn_msgs_software_version_to_proto(ros_msg.version, proto.version) - if ros_msg.body_tform_payload_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.body_tform_payload, proto.body_tform_payload) - if ros_msg.mount_tform_payload_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.mount_tform_payload, proto.mount_tform_payload) - proto.mount_frame_name = ros_msg.mount_frame_name.value - proto.liveness_timeout_secs = ros_msg.liveness_timeout_secs - proto.ipv4_address = ros_msg.ipv4_address - proto.link_speed = ros_msg.link_speed - if ros_msg.mass_volume_properties_is_set: - convert_bosdyn_msgs_payload_mass_volume_properties_to_proto(ros_msg.mass_volume_properties, proto.mass_volume_properties) - del proto.preset_configurations[:] - for _item in ros_msg.preset_configurations: - convert_bosdyn_msgs_payload_preset_to_proto(_item, proto.preset_configurations.add()) - - -def convert_proto_to_bosdyn_msgs_payload_preset(proto: "bosdyn.api.payload_pb2.PayloadPreset", ros_msg: "bosdyn_msgs.msgs.PayloadPreset") -> None: - ros_msg.preset_name = proto.preset_name - ros_msg.description = proto.description - convert_proto_to_geometry_msgs_pose(proto.mount_tform_payload, ros_msg.mount_tform_payload) - ros_msg.mount_tform_payload_is_set = proto.HasField("mount_tform_payload") - ros_msg.mount_frame_name.value = proto.mount_frame_name - convert_proto_to_bosdyn_msgs_payload_mass_volume_properties(proto.mass_volume_properties, ros_msg.mass_volume_properties) - ros_msg.mass_volume_properties_is_set = proto.HasField("mass_volume_properties") - ros_msg.label_prefix = [] - for _item in proto.label_prefix: - ros_msg.label_prefix.append(_item) - - -def convert_bosdyn_msgs_payload_preset_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadPreset", proto: "bosdyn.api.payload_pb2.PayloadPreset") -> None: - proto.Clear() - proto.preset_name = ros_msg.preset_name - proto.description = ros_msg.description - if ros_msg.mount_tform_payload_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.mount_tform_payload, proto.mount_tform_payload) - proto.mount_frame_name = ros_msg.mount_frame_name.value - if ros_msg.mass_volume_properties_is_set: - convert_bosdyn_msgs_payload_mass_volume_properties_to_proto(ros_msg.mass_volume_properties, proto.mass_volume_properties) - del proto.label_prefix[:] - for _item in ros_msg.label_prefix: - proto.label_prefix.append(_item) - - -def convert_proto_to_bosdyn_msgs_payload_mass_volume_properties(proto: "bosdyn.api.payload_pb2.PayloadMassVolumeProperties", ros_msg: "bosdyn_msgs.msgs.PayloadMassVolumeProperties") -> None: - ros_msg.total_mass = proto.total_mass - convert_proto_to_geometry_msgs_vector3(proto.com_pos_rt_payload, ros_msg.com_pos_rt_payload) - ros_msg.com_pos_rt_payload_is_set = proto.HasField("com_pos_rt_payload") - convert_proto_to_bosdyn_msgs_moment_of_intertia(proto.moi_tensor, ros_msg.moi_tensor) - ros_msg.moi_tensor_is_set = proto.HasField("moi_tensor") - from bosdyn_msgs.msg import Box3WithFrame - ros_msg.bounding_box = [] - for _item in proto.bounding_box: - ros_msg.bounding_box.append(Box3WithFrame()) - convert_proto_to_bosdyn_msgs_box3_with_frame(_item, ros_msg.bounding_box[-1]) - from bosdyn_msgs.msg import JointLimits - ros_msg.joint_limits = [] - for _item in proto.joint_limits: - ros_msg.joint_limits.append(JointLimits()) - convert_proto_to_bosdyn_msgs_joint_limits(_item, ros_msg.joint_limits[-1]) - - -def convert_bosdyn_msgs_payload_mass_volume_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadMassVolumeProperties", proto: "bosdyn.api.payload_pb2.PayloadMassVolumeProperties") -> None: - proto.Clear() - proto.total_mass = ros_msg.total_mass - if ros_msg.com_pos_rt_payload_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.com_pos_rt_payload, proto.com_pos_rt_payload) - if ros_msg.moi_tensor_is_set: - convert_bosdyn_msgs_moment_of_intertia_to_proto(ros_msg.moi_tensor, proto.moi_tensor) - del proto.bounding_box[:] - for _item in ros_msg.bounding_box: - convert_bosdyn_msgs_box3_with_frame_to_proto(_item, proto.bounding_box.add()) - del proto.joint_limits[:] - for _item in ros_msg.joint_limits: - convert_bosdyn_msgs_joint_limits_to_proto(_item, proto.joint_limits.add()) - - -def convert_proto_to_bosdyn_msgs_moment_of_intertia(proto: "bosdyn.api.payload_pb2.MomentOfIntertia", ros_msg: "bosdyn_msgs.msgs.MomentOfIntertia") -> None: - ros_msg.xx = proto.xx - ros_msg.yy = proto.yy - ros_msg.zz = proto.zz - ros_msg.xy = proto.xy - ros_msg.xz = proto.xz - ros_msg.yz = proto.yz - - -def convert_bosdyn_msgs_moment_of_intertia_to_proto(ros_msg: "bosdyn_msgs.msgs.MomentOfIntertia", proto: "bosdyn.api.payload_pb2.MomentOfIntertia") -> None: - proto.Clear() - proto.xx = ros_msg.xx - proto.yy = ros_msg.yy - proto.zz = ros_msg.zz - proto.xy = ros_msg.xy - proto.xz = ros_msg.xz - proto.yz = ros_msg.yz - - -def convert_proto_to_bosdyn_msgs_joint_limits(proto: "bosdyn.api.payload_pb2.JointLimits", ros_msg: "bosdyn_msgs.msgs.JointLimits") -> None: - ros_msg.label = proto.label - ros_msg.hy = [] - for _item in proto.hy: - ros_msg.hy.append(_item) - ros_msg.hx = [] - for _item in proto.hx: - ros_msg.hx.append(_item) - - -def convert_bosdyn_msgs_joint_limits_to_proto(ros_msg: "bosdyn_msgs.msgs.JointLimits", proto: "bosdyn.api.payload_pb2.JointLimits") -> None: - proto.Clear() - proto.label = ros_msg.label - del proto.hy[:] - for _item in ros_msg.hy: - proto.hy.append(_item) - del proto.hx[:] - for _item in ros_msg.hx: - proto.hx.append(_item) - - -def convert_proto_to_bosdyn_msgs_list_payloads_request(proto: "bosdyn.api.payload_pb2.ListPayloadsRequest", ros_msg: "bosdyn_msgs.msgs.ListPayloadsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_payloads_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPayloadsRequest", proto: "bosdyn.api.payload_pb2.ListPayloadsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_payloads_response(proto: "bosdyn.api.payload_pb2.ListPayloadsResponse", ros_msg: "bosdyn_msgs.msgs.ListPayloadsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Payload - ros_msg.payloads = [] - for _item in proto.payloads: - ros_msg.payloads.append(Payload()) - convert_proto_to_bosdyn_msgs_payload(_item, ros_msg.payloads[-1]) - - -def convert_bosdyn_msgs_list_payloads_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPayloadsResponse", proto: "bosdyn.api.payload_pb2.ListPayloadsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.payloads[:] - for _item in ros_msg.payloads: - convert_bosdyn_msgs_payload_to_proto(_item, proto.payloads.add()) - - -def convert_proto_to_bosdyn_msgs_mount_frame_name(proto: "bosdyn.api.payload_pb2.MountFrameName", ros_msg: "bosdyn_msgs.msgs.MountFrameName") -> None: - pass - - -def convert_bosdyn_msgs_mount_frame_name_to_proto(ros_msg: "bosdyn_msgs.msgs.MountFrameName", proto: "bosdyn.api.payload_pb2.MountFrameName") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_payload_estimation_command_request(proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Request", ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandRequest") -> None: - pass - - -def convert_bosdyn_msgs_payload_estimation_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandRequest", proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Request") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_payload_estimation_command_feedback_status(proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_payload_estimation_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedbackStatus", proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_payload_estimation_command_feedback_error(proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback.Error", ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedbackError") -> None: - pass - - -def convert_bosdyn_msgs_payload_estimation_command_feedback_error_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedbackError", proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_payload_estimation_command_feedback(proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.progress = proto.progress - ros_msg.error.value = proto.error - convert_proto_to_bosdyn_msgs_payload(proto.estimated_payload, ros_msg.estimated_payload) - ros_msg.estimated_payload_is_set = proto.HasField("estimated_payload") - - -def convert_bosdyn_msgs_payload_estimation_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommandFeedback", proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.progress = ros_msg.progress - proto.error = ros_msg.error.value - if ros_msg.estimated_payload_is_set: - convert_bosdyn_msgs_payload_to_proto(ros_msg.estimated_payload, proto.estimated_payload) - - -def convert_proto_to_bosdyn_msgs_payload_estimation_command(proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand", ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommand") -> None: - pass - - -def convert_bosdyn_msgs_payload_estimation_command_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadEstimationCommand", proto: "bosdyn.api.payload_estimation_pb2.PayloadEstimationCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_register_payload_request(proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadRequest", ros_msg: "bosdyn_msgs.msgs.RegisterPayloadRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_payload(proto.payload, ros_msg.payload) - ros_msg.payload_is_set = proto.HasField("payload") - ros_msg.payload_secret = proto.payload_secret - - -def convert_bosdyn_msgs_register_payload_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterPayloadRequest", proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.payload_is_set: - convert_bosdyn_msgs_payload_to_proto(ros_msg.payload, proto.payload) - proto.payload_secret = ros_msg.payload_secret - - -def convert_proto_to_bosdyn_msgs_register_payload_response_status(proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadResponse.Status", ros_msg: "bosdyn_msgs.msgs.RegisterPayloadResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_register_payload_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterPayloadResponseStatus", proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_register_payload_response(proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadResponse", ros_msg: "bosdyn_msgs.msgs.RegisterPayloadResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_register_payload_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RegisterPayloadResponse", proto: "bosdyn.api.payload_registration_pb2.RegisterPayloadResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_update_payload_version_request(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionRequest", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_payload_credentials(proto.payload_credentials, ros_msg.payload_credentials) - ros_msg.payload_credentials_is_set = proto.HasField("payload_credentials") - convert_proto_to_bosdyn_msgs_software_version(proto.updated_version, ros_msg.updated_version) - ros_msg.updated_version_is_set = proto.HasField("updated_version") - - -def convert_bosdyn_msgs_update_payload_version_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionRequest", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.payload_credentials_is_set: - convert_bosdyn_msgs_payload_credentials_to_proto(ros_msg.payload_credentials, proto.payload_credentials) - if ros_msg.updated_version_is_set: - convert_bosdyn_msgs_software_version_to_proto(ros_msg.updated_version, proto.updated_version) - - -def convert_proto_to_bosdyn_msgs_update_payload_version_response_status(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionResponse.Status", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_update_payload_version_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionResponseStatus", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_payload_version_response(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionResponse", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_update_payload_version_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadVersionResponse", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadVersionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_get_payload_auth_token_request(proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenRequest", ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_payload_credentials(proto.payload_credentials, ros_msg.payload_credentials) - ros_msg.payload_credentials_is_set = proto.HasField("payload_credentials") - - -def convert_bosdyn_msgs_get_payload_auth_token_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenRequest", proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.payload_credentials_is_set: - convert_bosdyn_msgs_payload_credentials_to_proto(ros_msg.payload_credentials, proto.payload_credentials) - - -def convert_proto_to_bosdyn_msgs_get_payload_auth_token_response_status(proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenResponse.Status", ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_get_payload_auth_token_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenResponseStatus", proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_payload_auth_token_response(proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenResponse", ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.token = proto.token - - -def convert_bosdyn_msgs_get_payload_auth_token_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPayloadAuthTokenResponse", proto: "bosdyn.api.payload_registration_pb2.GetPayloadAuthTokenResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.token = ros_msg.token - - -def convert_proto_to_bosdyn_msgs_update_payload_attached_request_request(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedRequest.Request", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedRequestRequest") -> None: - pass - - -def convert_bosdyn_msgs_update_payload_attached_request_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedRequestRequest", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedRequest.Request") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_payload_attached_request(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedRequest", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_payload_credentials(proto.payload_credentials, ros_msg.payload_credentials) - ros_msg.payload_credentials_is_set = proto.HasField("payload_credentials") - ros_msg.request.value = proto.request - - -def convert_bosdyn_msgs_update_payload_attached_request_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedRequest", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.payload_credentials_is_set: - convert_bosdyn_msgs_payload_credentials_to_proto(ros_msg.payload_credentials, proto.payload_credentials) - proto.request = ros_msg.request.value - - -def convert_proto_to_bosdyn_msgs_update_payload_attached_response_status(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedResponse.Status", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_update_payload_attached_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedResponseStatus", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_update_payload_attached_response(proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedResponse", ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_update_payload_attached_response_to_proto(ros_msg: "bosdyn_msgs.msgs.UpdatePayloadAttachedResponse", proto: "bosdyn.api.payload_registration_pb2.UpdatePayloadAttachedResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_payload_credentials(proto: "bosdyn.api.payload_registration_pb2.PayloadCredentials", ros_msg: "bosdyn_msgs.msgs.PayloadCredentials") -> None: - ros_msg.guid = proto.guid - ros_msg.secret = proto.secret - - -def convert_bosdyn_msgs_payload_credentials_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadCredentials", proto: "bosdyn.api.payload_registration_pb2.PayloadCredentials") -> None: - proto.Clear() - proto.guid = ros_msg.guid - proto.secret = ros_msg.secret - - -def convert_proto_to_bosdyn_msgs_point_cloud_source(proto: "bosdyn.api.point_cloud_pb2.PointCloudSource", ros_msg: "bosdyn_msgs.msgs.PointCloudSource") -> None: - ros_msg.name = proto.name - ros_msg.frame_name_sensor = proto.frame_name_sensor - convert_proto_to_builtin_interfaces_time(proto.acquisition_time, ros_msg.acquisition_time) - ros_msg.acquisition_time_is_set = proto.HasField("acquisition_time") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - - -def convert_bosdyn_msgs_point_cloud_source_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudSource", proto: "bosdyn.api.point_cloud_pb2.PointCloudSource") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.frame_name_sensor = ros_msg.frame_name_sensor - if ros_msg.acquisition_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.acquisition_time, proto.acquisition_time) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - - -def convert_proto_to_bosdyn_msgs_point_cloud_encoding(proto: "bosdyn.api.point_cloud_pb2.PointCloud.Encoding", ros_msg: "bosdyn_msgs.msgs.PointCloudEncoding") -> None: - pass - - -def convert_bosdyn_msgs_point_cloud_encoding_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudEncoding", proto: "bosdyn.api.point_cloud_pb2.PointCloud.Encoding") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_point_cloud_encoding_parameters(proto: "bosdyn.api.point_cloud_pb2.PointCloud.EncodingParameters", ros_msg: "bosdyn_msgs.msgs.PointCloudEncodingParameters") -> None: - ros_msg.scale_factor = proto.scale_factor - ros_msg.max_x = proto.max_x - ros_msg.max_y = proto.max_y - ros_msg.max_z = proto.max_z - ros_msg.remapping_constant = proto.remapping_constant - ros_msg.bytes_per_point = proto.bytes_per_point - - -def convert_bosdyn_msgs_point_cloud_encoding_parameters_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudEncodingParameters", proto: "bosdyn.api.point_cloud_pb2.PointCloud.EncodingParameters") -> None: - proto.Clear() - proto.scale_factor = ros_msg.scale_factor - proto.max_x = ros_msg.max_x - proto.max_y = ros_msg.max_y - proto.max_z = ros_msg.max_z - proto.remapping_constant = ros_msg.remapping_constant - proto.bytes_per_point = ros_msg.bytes_per_point - - -def convert_proto_to_bosdyn_msgs_point_cloud(proto: "bosdyn.api.point_cloud_pb2.PointCloud", ros_msg: "bosdyn_msgs.msgs.PointCloud") -> None: - convert_proto_to_bosdyn_msgs_point_cloud_source(proto.source, ros_msg.source) - ros_msg.source_is_set = proto.HasField("source") - ros_msg.num_points = proto.num_points - ros_msg.encoding.value = proto.encoding - convert_proto_to_bosdyn_msgs_point_cloud_encoding_parameters(proto.encoding_parameters, ros_msg.encoding_parameters) - ros_msg.encoding_parameters_is_set = proto.HasField("encoding_parameters") - ros_msg.data = proto.data - - -def convert_bosdyn_msgs_point_cloud_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloud", proto: "bosdyn.api.point_cloud_pb2.PointCloud") -> None: - proto.Clear() - if ros_msg.source_is_set: - convert_bosdyn_msgs_point_cloud_source_to_proto(ros_msg.source, proto.source) - proto.num_points = ros_msg.num_points - proto.encoding = ros_msg.encoding.value - if ros_msg.encoding_parameters_is_set: - convert_bosdyn_msgs_point_cloud_encoding_parameters_to_proto(ros_msg.encoding_parameters, proto.encoding_parameters) - proto.data = ros_msg.data - - -def convert_proto_to_bosdyn_msgs_list_point_cloud_sources_request(proto: "bosdyn.api.point_cloud_pb2.ListPointCloudSourcesRequest", ros_msg: "bosdyn_msgs.msgs.ListPointCloudSourcesRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_point_cloud_sources_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPointCloudSourcesRequest", proto: "bosdyn.api.point_cloud_pb2.ListPointCloudSourcesRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_point_cloud_sources_response(proto: "bosdyn.api.point_cloud_pb2.ListPointCloudSourcesResponse", ros_msg: "bosdyn_msgs.msgs.ListPointCloudSourcesResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import PointCloudSource - ros_msg.point_cloud_sources = [] - for _item in proto.point_cloud_sources: - ros_msg.point_cloud_sources.append(PointCloudSource()) - convert_proto_to_bosdyn_msgs_point_cloud_source(_item, ros_msg.point_cloud_sources[-1]) - - -def convert_bosdyn_msgs_list_point_cloud_sources_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPointCloudSourcesResponse", proto: "bosdyn.api.point_cloud_pb2.ListPointCloudSourcesResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.point_cloud_sources[:] - for _item in ros_msg.point_cloud_sources: - convert_bosdyn_msgs_point_cloud_source_to_proto(_item, proto.point_cloud_sources.add()) - - -def convert_proto_to_bosdyn_msgs_point_cloud_request(proto: "bosdyn.api.point_cloud_pb2.PointCloudRequest", ros_msg: "bosdyn_msgs.msgs.PointCloudRequest") -> None: - ros_msg.point_cloud_source_name = proto.point_cloud_source_name - - -def convert_bosdyn_msgs_point_cloud_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudRequest", proto: "bosdyn.api.point_cloud_pb2.PointCloudRequest") -> None: - proto.Clear() - proto.point_cloud_source_name = ros_msg.point_cloud_source_name - - -def convert_proto_to_bosdyn_msgs_get_point_cloud_request(proto: "bosdyn.api.point_cloud_pb2.GetPointCloudRequest", ros_msg: "bosdyn_msgs.msgs.GetPointCloudRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import PointCloudRequest - ros_msg.point_cloud_requests = [] - for _item in proto.point_cloud_requests: - ros_msg.point_cloud_requests.append(PointCloudRequest()) - convert_proto_to_bosdyn_msgs_point_cloud_request(_item, ros_msg.point_cloud_requests[-1]) - - -def convert_bosdyn_msgs_get_point_cloud_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPointCloudRequest", proto: "bosdyn.api.point_cloud_pb2.GetPointCloudRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.point_cloud_requests[:] - for _item in ros_msg.point_cloud_requests: - convert_bosdyn_msgs_point_cloud_request_to_proto(_item, proto.point_cloud_requests.add()) - - -def convert_proto_to_bosdyn_msgs_point_cloud_response_status(proto: "bosdyn.api.point_cloud_pb2.PointCloudResponse.Status", ros_msg: "bosdyn_msgs.msgs.PointCloudResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_point_cloud_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudResponseStatus", proto: "bosdyn.api.point_cloud_pb2.PointCloudResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_point_cloud_response(proto: "bosdyn.api.point_cloud_pb2.PointCloudResponse", ros_msg: "bosdyn_msgs.msgs.PointCloudResponse") -> None: - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_point_cloud(proto.point_cloud, ros_msg.point_cloud) - ros_msg.point_cloud_is_set = proto.HasField("point_cloud") - - -def convert_bosdyn_msgs_point_cloud_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PointCloudResponse", proto: "bosdyn.api.point_cloud_pb2.PointCloudResponse") -> None: - proto.Clear() - proto.status = ros_msg.status.value - if ros_msg.point_cloud_is_set: - convert_bosdyn_msgs_point_cloud_to_proto(ros_msg.point_cloud, proto.point_cloud) - - -def convert_proto_to_bosdyn_msgs_get_point_cloud_response(proto: "bosdyn.api.point_cloud_pb2.GetPointCloudResponse", ros_msg: "bosdyn_msgs.msgs.GetPointCloudResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import PointCloudResponse - ros_msg.point_cloud_responses = [] - for _item in proto.point_cloud_responses: - ros_msg.point_cloud_responses.append(PointCloudResponse()) - convert_proto_to_bosdyn_msgs_point_cloud_response(_item, ros_msg.point_cloud_responses[-1]) - - -def convert_bosdyn_msgs_get_point_cloud_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPointCloudResponse", proto: "bosdyn.api.point_cloud_pb2.GetPointCloudResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.point_cloud_responses[:] - for _item in ros_msg.point_cloud_responses: - convert_bosdyn_msgs_point_cloud_response_to_proto(_item, proto.point_cloud_responses.add()) - - -def convert_proto_to_bosdyn_msgs_power_command_status(proto: "bosdyn.api.power_pb2.PowerCommandStatus", ros_msg: "bosdyn_msgs.msgs.PowerCommandStatus") -> None: - pass - - -def convert_bosdyn_msgs_power_command_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandStatus", proto: "bosdyn.api.power_pb2.PowerCommandStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_command_request_request(proto: "bosdyn.api.power_pb2.PowerCommandRequest.Request", ros_msg: "bosdyn_msgs.msgs.PowerCommandRequestRequest") -> None: - pass - - -def convert_bosdyn_msgs_power_command_request_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandRequestRequest", proto: "bosdyn.api.power_pb2.PowerCommandRequest.Request") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_command_request(proto: "bosdyn.api.power_pb2.PowerCommandRequest", ros_msg: "bosdyn_msgs.msgs.PowerCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.request.value = proto.request - - -def convert_bosdyn_msgs_power_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandRequest", proto: "bosdyn.api.power_pb2.PowerCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.request = ros_msg.request.value - - -def convert_proto_to_bosdyn_msgs_power_command_response(proto: "bosdyn.api.power_pb2.PowerCommandResponse", ros_msg: "bosdyn_msgs.msgs.PowerCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.power_command_id = proto.power_command_id - ros_msg.license_status.value = proto.license_status - from bosdyn_msgs.msg import SystemFault - ros_msg.blocking_faults = [] - for _item in proto.blocking_faults: - ros_msg.blocking_faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.blocking_faults[-1]) - - -def convert_bosdyn_msgs_power_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandResponse", proto: "bosdyn.api.power_pb2.PowerCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.power_command_id = ros_msg.power_command_id - proto.license_status = ros_msg.license_status.value - del proto.blocking_faults[:] - for _item in ros_msg.blocking_faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.blocking_faults.add()) - - -def convert_proto_to_bosdyn_msgs_power_command_feedback_request(proto: "bosdyn.api.power_pb2.PowerCommandFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.PowerCommandFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.power_command_id = proto.power_command_id - - -def convert_bosdyn_msgs_power_command_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandFeedbackRequest", proto: "bosdyn.api.power_pb2.PowerCommandFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.power_command_id = ros_msg.power_command_id - - -def convert_proto_to_bosdyn_msgs_power_command_feedback_response(proto: "bosdyn.api.power_pb2.PowerCommandFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.PowerCommandFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - from bosdyn_msgs.msg import SystemFault - ros_msg.blocking_faults = [] - for _item in proto.blocking_faults: - ros_msg.blocking_faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.blocking_faults[-1]) - - -def convert_bosdyn_msgs_power_command_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerCommandFeedbackResponse", proto: "bosdyn.api.power_pb2.PowerCommandFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - del proto.blocking_faults[:] - for _item in ros_msg.blocking_faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.blocking_faults.add()) - - -def convert_proto_to_bosdyn_msgs_fan_power_command_request(proto: "bosdyn.api.power_pb2.FanPowerCommandRequest", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.percent_power = proto.percent_power - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - ros_msg.duration_is_set = proto.HasField("duration") - - -def convert_bosdyn_msgs_fan_power_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandRequest", proto: "bosdyn.api.power_pb2.FanPowerCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.percent_power = ros_msg.percent_power - if ros_msg.duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - - -def convert_proto_to_bosdyn_msgs_fan_power_command_response_status(proto: "bosdyn.api.power_pb2.FanPowerCommandResponse.Status", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_fan_power_command_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandResponseStatus", proto: "bosdyn.api.power_pb2.FanPowerCommandResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_fan_power_command_response(proto: "bosdyn.api.power_pb2.FanPowerCommandResponse", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - convert_proto_to_builtin_interfaces_time(proto.desired_end_time, ros_msg.desired_end_time) - ros_msg.desired_end_time_is_set = proto.HasField("desired_end_time") - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_fan_power_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandResponse", proto: "bosdyn.api.power_pb2.FanPowerCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - if ros_msg.desired_end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.desired_end_time, proto.desired_end_time) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_fan_power_command_feedback_request(proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.command_id = proto.command_id - - -def convert_bosdyn_msgs_fan_power_command_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackRequest", proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.command_id = ros_msg.command_id - - -def convert_proto_to_bosdyn_msgs_fan_power_command_feedback_response_status(proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_fan_power_command_feedback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackResponseStatus", proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_fan_power_command_feedback_response(proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_builtin_interfaces_time(proto.desired_end_time, ros_msg.desired_end_time) - ros_msg.desired_end_time_is_set = proto.HasField("desired_end_time") - convert_proto_to_builtin_interfaces_time(proto.early_stop_time, ros_msg.early_stop_time) - ros_msg.early_stop_time_is_set = proto.HasField("early_stop_time") - - -def convert_bosdyn_msgs_fan_power_command_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.FanPowerCommandFeedbackResponse", proto: "bosdyn.api.power_pb2.FanPowerCommandFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.desired_end_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.desired_end_time, proto.desired_end_time) - if ros_msg.early_stop_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.early_stop_time, proto.early_stop_time) - - -def convert_proto_to_bosdyn_msgs_raycast_request(proto: "bosdyn.api.ray_cast_pb2.RaycastRequest", ros_msg: "bosdyn_msgs.msgs.RaycastRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.ray_frame_name = proto.ray_frame_name - convert_proto_to_bosdyn_msgs_ray(proto.ray, ros_msg.ray) - ros_msg.ray_is_set = proto.HasField("ray") - ros_msg.min_intersection_distance = proto.min_intersection_distance - from bosdyn_msgs.msg import RayIntersectionType - ros_msg.intersection_types = [] - for _item in proto.intersection_types: - ros_msg.intersection_types.append(RayIntersectionType()) - ros_msg.intersection_types[-1].value = _item - - -def convert_bosdyn_msgs_raycast_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RaycastRequest", proto: "bosdyn.api.ray_cast_pb2.RaycastRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.ray_frame_name = ros_msg.ray_frame_name - if ros_msg.ray_is_set: - convert_bosdyn_msgs_ray_to_proto(ros_msg.ray, proto.ray) - proto.min_intersection_distance = ros_msg.min_intersection_distance - del proto.intersection_types[:] - for _item in ros_msg.intersection_types: - proto.intersection_types.append(_item.value) - - -def convert_proto_to_bosdyn_msgs_ray_intersection_type(proto: "bosdyn.api.ray_cast_pb2.RayIntersection.Type", ros_msg: "bosdyn_msgs.msgs.RayIntersectionType") -> None: - pass - - -def convert_bosdyn_msgs_ray_intersection_type_to_proto(ros_msg: "bosdyn_msgs.msgs.RayIntersectionType", proto: "bosdyn.api.ray_cast_pb2.RayIntersection.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ray_intersection(proto: "bosdyn.api.ray_cast_pb2.RayIntersection", ros_msg: "bosdyn_msgs.msgs.RayIntersection") -> None: - ros_msg.type.value = proto.type - convert_proto_to_geometry_msgs_vector3(proto.hit_position_in_hit_frame, ros_msg.hit_position_in_hit_frame) - ros_msg.hit_position_in_hit_frame_is_set = proto.HasField("hit_position_in_hit_frame") - ros_msg.distance_meters = proto.distance_meters - - -def convert_bosdyn_msgs_ray_intersection_to_proto(ros_msg: "bosdyn_msgs.msgs.RayIntersection", proto: "bosdyn.api.ray_cast_pb2.RayIntersection") -> None: - proto.Clear() - proto.type = ros_msg.type.value - if ros_msg.hit_position_in_hit_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.hit_position_in_hit_frame, proto.hit_position_in_hit_frame) - proto.distance_meters = ros_msg.distance_meters - - -def convert_proto_to_bosdyn_msgs_raycast_response_status(proto: "bosdyn.api.ray_cast_pb2.RaycastResponse.Status", ros_msg: "bosdyn_msgs.msgs.RaycastResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_raycast_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RaycastResponseStatus", proto: "bosdyn.api.ray_cast_pb2.RaycastResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_raycast_response(proto: "bosdyn.api.ray_cast_pb2.RaycastResponse", ros_msg: "bosdyn_msgs.msgs.RaycastResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.message = proto.message - ros_msg.hit_frame_name = proto.hit_frame_name - from bosdyn_msgs.msg import RayIntersection - ros_msg.hits = [] - for _item in proto.hits: - ros_msg.hits.append(RayIntersection()) - convert_proto_to_bosdyn_msgs_ray_intersection(_item, ros_msg.hits[-1]) - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - - -def convert_bosdyn_msgs_raycast_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RaycastResponse", proto: "bosdyn.api.ray_cast_pb2.RaycastResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.message = ros_msg.message - proto.hit_frame_name = ros_msg.hit_frame_name - del proto.hits[:] - for _item in ros_msg.hits: - convert_bosdyn_msgs_ray_intersection_to_proto(_item, proto.hits.add()) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - - -def convert_proto_to_bosdyn_msgs_robot_command_one_of_command(proto: "bosdyn.api.robot_command_pb2.RobotCommand", ros_msg: "bosdyn_msgs.msgs.RobotCommandOneOfCommand") -> None: - if proto.HasField("full_body_command"): - ros_msg.command_choice = ros_msg.COMMAND_FULL_BODY_COMMAND_SET - convert_proto_to_bosdyn_msgs_full_body_command_request(proto.full_body_command, ros_msg.full_body_command) - if proto.HasField("synchronized_command"): - ros_msg.command_choice = ros_msg.COMMAND_SYNCHRONIZED_COMMAND_SET - convert_proto_to_bosdyn_msgs_synchronized_command_request(proto.synchronized_command, ros_msg.synchronized_command) - - -def convert_bosdyn_msgs_robot_command_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandOneOfCommand", proto: "bosdyn.api.robot_command_pb2.RobotCommand") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_FULL_BODY_COMMAND_SET: - convert_bosdyn_msgs_full_body_command_request_to_proto(ros_msg.full_body_command, proto.full_body_command) - if ros_msg.command_choice == ros_msg.COMMAND_SYNCHRONIZED_COMMAND_SET: - convert_bosdyn_msgs_synchronized_command_request_to_proto(ros_msg.synchronized_command, proto.synchronized_command) - - -def convert_proto_to_bosdyn_msgs_robot_command(proto: "bosdyn.api.robot_command_pb2.RobotCommand", ros_msg: "bosdyn_msgs.msgs.RobotCommand") -> None: - convert_proto_to_bosdyn_msgs_robot_command_one_of_command(proto, ros_msg.command) - - -def convert_bosdyn_msgs_robot_command_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommand", proto: "bosdyn.api.robot_command_pb2.RobotCommand") -> None: - proto.Clear() - convert_bosdyn_msgs_robot_command_one_of_command_to_proto(ros_msg.command, proto) - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_one_of_command(proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedback", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackOneOfCommand") -> None: - if proto.HasField("full_body_feedback"): - ros_msg.command_choice = ros_msg.COMMAND_FULL_BODY_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_full_body_command_feedback(proto.full_body_feedback, ros_msg.full_body_feedback) - if proto.HasField("synchronized_feedback"): - ros_msg.command_choice = ros_msg.COMMAND_SYNCHRONIZED_FEEDBACK_SET - convert_proto_to_bosdyn_msgs_synchronized_command_feedback(proto.synchronized_feedback, ros_msg.synchronized_feedback) - - -def convert_bosdyn_msgs_robot_command_feedback_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackOneOfCommand", proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedback") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_FULL_BODY_FEEDBACK_SET: - convert_bosdyn_msgs_full_body_command_feedback_to_proto(ros_msg.full_body_feedback, proto.full_body_feedback) - if ros_msg.command_choice == ros_msg.COMMAND_SYNCHRONIZED_FEEDBACK_SET: - convert_bosdyn_msgs_synchronized_command_feedback_to_proto(ros_msg.synchronized_feedback, proto.synchronized_feedback) - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback(proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedback", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_robot_command_feedback_one_of_command(proto, ros_msg.command) - - -def convert_bosdyn_msgs_robot_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedback", proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedback") -> None: - proto.Clear() - convert_bosdyn_msgs_robot_command_feedback_one_of_command_to_proto(ros_msg.command, proto) - - -def convert_proto_to_bosdyn_msgs_robot_command_request(proto: "bosdyn.api.robot_command_pb2.RobotCommandRequest", ros_msg: "bosdyn_msgs.msgs.RobotCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_robot_command(proto.command, ros_msg.command) - ros_msg.command_is_set = proto.HasField("command") - ros_msg.clock_identifier = proto.clock_identifier - - -def convert_bosdyn_msgs_robot_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandRequest", proto: "bosdyn.api.robot_command_pb2.RobotCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.command_is_set: - convert_bosdyn_msgs_robot_command_to_proto(ros_msg.command, proto.command) - proto.clock_identifier = ros_msg.clock_identifier - - -def convert_proto_to_bosdyn_msgs_robot_command_response_status(proto: "bosdyn.api.robot_command_pb2.RobotCommandResponse.Status", ros_msg: "bosdyn_msgs.msgs.RobotCommandResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_robot_command_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandResponseStatus", proto: "bosdyn.api.robot_command_pb2.RobotCommandResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_robot_command_response(proto: "bosdyn.api.robot_command_pb2.RobotCommandResponse", ros_msg: "bosdyn_msgs.msgs.RobotCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.message = proto.message - ros_msg.robot_command_id = proto.robot_command_id - - -def convert_bosdyn_msgs_robot_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandResponse", proto: "bosdyn.api.robot_command_pb2.RobotCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.message = ros_msg.message - proto.robot_command_id = ros_msg.robot_command_id - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_request(proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.robot_command_id = proto.robot_command_id - - -def convert_bosdyn_msgs_robot_command_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackRequest", proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.robot_command_id = ros_msg.robot_command_id - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_response_status(proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_robot_command_feedback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackResponseStatus", proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_robot_command_feedback_response(proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - convert_proto_to_bosdyn_msgs_robot_command_feedback(proto.feedback, ros_msg.feedback) - ros_msg.feedback_is_set = proto.HasField("feedback") - - -def convert_bosdyn_msgs_robot_command_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotCommandFeedbackResponse", proto: "bosdyn.api.robot_command_pb2.RobotCommandFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - if ros_msg.feedback_is_set: - convert_bosdyn_msgs_robot_command_feedback_to_proto(ros_msg.feedback, proto.feedback) - - -def convert_proto_to_bosdyn_msgs_clear_behavior_fault_request(proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultRequest", ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.behavior_fault_id = proto.behavior_fault_id - - -def convert_bosdyn_msgs_clear_behavior_fault_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultRequest", proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.behavior_fault_id = ros_msg.behavior_fault_id - - -def convert_proto_to_bosdyn_msgs_clear_behavior_fault_response_status(proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultResponse.Status", ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_clear_behavior_fault_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultResponseStatus", proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_clear_behavior_fault_response(proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultResponse", ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_behavior_fault(proto.behavior_fault, ros_msg.behavior_fault) - ros_msg.behavior_fault_is_set = proto.HasField("behavior_fault") - from bosdyn_msgs.msg import SystemFault - ros_msg.blocking_system_faults = [] - for _item in proto.blocking_system_faults: - ros_msg.blocking_system_faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.blocking_system_faults[-1]) - - -def convert_bosdyn_msgs_clear_behavior_fault_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBehaviorFaultResponse", proto: "bosdyn.api.robot_command_pb2.ClearBehaviorFaultResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - if ros_msg.behavior_fault_is_set: - convert_bosdyn_msgs_behavior_fault_to_proto(ros_msg.behavior_fault, proto.behavior_fault) - del proto.blocking_system_faults[:] - for _item in ros_msg.blocking_system_faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.blocking_system_faults.add()) - - -def convert_proto_to_bosdyn_msgs_robot_id(proto: "bosdyn.api.robot_id_pb2.RobotId", ros_msg: "bosdyn_msgs.msgs.RobotId") -> None: - ros_msg.serial_number = proto.serial_number - ros_msg.species = proto.species - ros_msg.version = proto.version - convert_proto_to_bosdyn_msgs_robot_software_release(proto.software_release, ros_msg.software_release) - ros_msg.software_release_is_set = proto.HasField("software_release") - ros_msg.nickname = proto.nickname - ros_msg.computer_serial_number = proto.computer_serial_number - - -def convert_bosdyn_msgs_robot_id_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotId", proto: "bosdyn.api.robot_id_pb2.RobotId") -> None: - proto.Clear() - proto.serial_number = ros_msg.serial_number - proto.species = ros_msg.species - proto.version = ros_msg.version - if ros_msg.software_release_is_set: - convert_bosdyn_msgs_robot_software_release_to_proto(ros_msg.software_release, proto.software_release) - proto.nickname = ros_msg.nickname - proto.computer_serial_number = ros_msg.computer_serial_number - - -def convert_proto_to_bosdyn_msgs_software_version(proto: "bosdyn.api.robot_id_pb2.SoftwareVersion", ros_msg: "bosdyn_msgs.msgs.SoftwareVersion") -> None: - ros_msg.major_version = proto.major_version - ros_msg.minor_version = proto.minor_version - ros_msg.patch_level = proto.patch_level - - -def convert_bosdyn_msgs_software_version_to_proto(ros_msg: "bosdyn_msgs.msgs.SoftwareVersion", proto: "bosdyn.api.robot_id_pb2.SoftwareVersion") -> None: - proto.Clear() - proto.major_version = ros_msg.major_version - proto.minor_version = ros_msg.minor_version - proto.patch_level = ros_msg.patch_level - - -def convert_proto_to_bosdyn_msgs_robot_software_release(proto: "bosdyn.api.robot_id_pb2.RobotSoftwareRelease", ros_msg: "bosdyn_msgs.msgs.RobotSoftwareRelease") -> None: - convert_proto_to_bosdyn_msgs_software_version(proto.version, ros_msg.version) - ros_msg.version_is_set = proto.HasField("version") - ros_msg.name = proto.name - ros_msg.type = proto.type - convert_proto_to_builtin_interfaces_time(proto.changeset_date, ros_msg.changeset_date) - ros_msg.changeset_date_is_set = proto.HasField("changeset_date") - ros_msg.changeset = proto.changeset - ros_msg.api_version = proto.api_version - ros_msg.build_information = proto.build_information - convert_proto_to_builtin_interfaces_time(proto.install_date, ros_msg.install_date) - ros_msg.install_date_is_set = proto.HasField("install_date") - from bosdyn_msgs.msg import Parameter - ros_msg.parameters = [] - for _item in proto.parameters: - ros_msg.parameters.append(Parameter()) - convert_proto_to_bosdyn_msgs_parameter(_item, ros_msg.parameters[-1]) - - -def convert_bosdyn_msgs_robot_software_release_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotSoftwareRelease", proto: "bosdyn.api.robot_id_pb2.RobotSoftwareRelease") -> None: - proto.Clear() - if ros_msg.version_is_set: - convert_bosdyn_msgs_software_version_to_proto(ros_msg.version, proto.version) - proto.name = ros_msg.name - proto.type = ros_msg.type - if ros_msg.changeset_date_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.changeset_date, proto.changeset_date) - proto.changeset = ros_msg.changeset - proto.api_version = ros_msg.api_version - proto.build_information = ros_msg.build_information - if ros_msg.install_date_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.install_date, proto.install_date) - del proto.parameters[:] - for _item in ros_msg.parameters: - convert_bosdyn_msgs_parameter_to_proto(_item, proto.parameters.add()) - - -def convert_proto_to_bosdyn_msgs_robot_id_request(proto: "bosdyn.api.robot_id_pb2.RobotIdRequest", ros_msg: "bosdyn_msgs.msgs.RobotIdRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_robot_id_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotIdRequest", proto: "bosdyn.api.robot_id_pb2.RobotIdRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_robot_id_response(proto: "bosdyn.api.robot_id_pb2.RobotIdResponse", ros_msg: "bosdyn_msgs.msgs.RobotIdResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_robot_id(proto.robot_id, ros_msg.robot_id) - ros_msg.robot_id_is_set = proto.HasField("robot_id") - - -def convert_bosdyn_msgs_robot_id_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotIdResponse", proto: "bosdyn.api.robot_id_pb2.RobotIdResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.robot_id_is_set: - convert_bosdyn_msgs_robot_id_to_proto(ros_msg.robot_id, proto.robot_id) - - -def convert_proto_to_bosdyn_msgs_skeleton_link_obj_model(proto: "bosdyn.api.robot_state_pb2.Skeleton.Link.ObjModel", ros_msg: "bosdyn_msgs.msgs.SkeletonLinkObjModel") -> None: - ros_msg.file_name = proto.file_name - ros_msg.file_contents = proto.file_contents - - -def convert_bosdyn_msgs_skeleton_link_obj_model_to_proto(ros_msg: "bosdyn_msgs.msgs.SkeletonLinkObjModel", proto: "bosdyn.api.robot_state_pb2.Skeleton.Link.ObjModel") -> None: - proto.Clear() - proto.file_name = ros_msg.file_name - proto.file_contents = ros_msg.file_contents - - -def convert_proto_to_bosdyn_msgs_skeleton_link(proto: "bosdyn.api.robot_state_pb2.Skeleton.Link", ros_msg: "bosdyn_msgs.msgs.SkeletonLink") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_skeleton_link_obj_model(proto.obj_model, ros_msg.obj_model) - ros_msg.obj_model_is_set = proto.HasField("obj_model") - - -def convert_bosdyn_msgs_skeleton_link_to_proto(ros_msg: "bosdyn_msgs.msgs.SkeletonLink", proto: "bosdyn.api.robot_state_pb2.Skeleton.Link") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.obj_model_is_set: - convert_bosdyn_msgs_skeleton_link_obj_model_to_proto(ros_msg.obj_model, proto.obj_model) - - -def convert_proto_to_bosdyn_msgs_skeleton(proto: "bosdyn.api.robot_state_pb2.Skeleton", ros_msg: "bosdyn_msgs.msgs.Skeleton") -> None: - from bosdyn_msgs.msg import SkeletonLink - ros_msg.links = [] - for _item in proto.links: - ros_msg.links.append(SkeletonLink()) - convert_proto_to_bosdyn_msgs_skeleton_link(_item, ros_msg.links[-1]) - ros_msg.urdf = proto.urdf - - -def convert_bosdyn_msgs_skeleton_to_proto(ros_msg: "bosdyn_msgs.msgs.Skeleton", proto: "bosdyn.api.robot_state_pb2.Skeleton") -> None: - proto.Clear() - del proto.links[:] - for _item in ros_msg.links: - convert_bosdyn_msgs_skeleton_link_to_proto(_item, proto.links.add()) - proto.urdf = ros_msg.urdf - - -def convert_proto_to_bosdyn_msgs_hardware_configuration(proto: "bosdyn.api.robot_state_pb2.HardwareConfiguration", ros_msg: "bosdyn_msgs.msgs.HardwareConfiguration") -> None: - convert_proto_to_bosdyn_msgs_skeleton(proto.skeleton, ros_msg.skeleton) - ros_msg.skeleton_is_set = proto.HasField("skeleton") - ros_msg.can_power_command_request_off_robot = proto.can_power_command_request_off_robot - ros_msg.can_power_command_request_cycle_robot = proto.can_power_command_request_cycle_robot - ros_msg.can_power_command_request_payload_ports = proto.can_power_command_request_payload_ports - ros_msg.can_power_command_request_wifi_radio = proto.can_power_command_request_wifi_radio - ros_msg.has_audio_visual_system = proto.has_audio_visual_system - - -def convert_bosdyn_msgs_hardware_configuration_to_proto(ros_msg: "bosdyn_msgs.msgs.HardwareConfiguration", proto: "bosdyn.api.robot_state_pb2.HardwareConfiguration") -> None: - proto.Clear() - if ros_msg.skeleton_is_set: - convert_bosdyn_msgs_skeleton_to_proto(ros_msg.skeleton, proto.skeleton) - proto.can_power_command_request_off_robot = ros_msg.can_power_command_request_off_robot - proto.can_power_command_request_cycle_robot = ros_msg.can_power_command_request_cycle_robot - proto.can_power_command_request_payload_ports = ros_msg.can_power_command_request_payload_ports - proto.can_power_command_request_wifi_radio = ros_msg.can_power_command_request_wifi_radio - proto.has_audio_visual_system = ros_msg.has_audio_visual_system - - -def convert_proto_to_bosdyn_msgs_robot_state(proto: "bosdyn.api.robot_state_pb2.RobotState", ros_msg: "bosdyn_msgs.msgs.RobotState") -> None: - convert_proto_to_bosdyn_msgs_power_state(proto.power_state, ros_msg.power_state) - ros_msg.power_state_is_set = proto.HasField("power_state") - from bosdyn_msgs.msg import BatteryState - ros_msg.battery_states = [] - for _item in proto.battery_states: - ros_msg.battery_states.append(BatteryState()) - convert_proto_to_bosdyn_msgs_battery_state(_item, ros_msg.battery_states[-1]) - from bosdyn_msgs.msg import CommsState - ros_msg.comms_states = [] - for _item in proto.comms_states: - ros_msg.comms_states.append(CommsState()) - convert_proto_to_bosdyn_msgs_comms_state(_item, ros_msg.comms_states[-1]) - convert_proto_to_bosdyn_msgs_system_fault_state(proto.system_fault_state, ros_msg.system_fault_state) - ros_msg.system_fault_state_is_set = proto.HasField("system_fault_state") - from bosdyn_msgs.msg import EStopState - ros_msg.estop_states = [] - for _item in proto.estop_states: - ros_msg.estop_states.append(EStopState()) - convert_proto_to_bosdyn_msgs_e_stop_state(_item, ros_msg.estop_states[-1]) - convert_proto_to_bosdyn_msgs_kinematic_state(proto.kinematic_state, ros_msg.kinematic_state) - ros_msg.kinematic_state_is_set = proto.HasField("kinematic_state") - convert_proto_to_bosdyn_msgs_behavior_fault_state(proto.behavior_fault_state, ros_msg.behavior_fault_state) - ros_msg.behavior_fault_state_is_set = proto.HasField("behavior_fault_state") - from bosdyn_msgs.msg import FootState - ros_msg.foot_state = [] - for _item in proto.foot_state: - ros_msg.foot_state.append(FootState()) - convert_proto_to_bosdyn_msgs_foot_state(_item, ros_msg.foot_state[-1]) - convert_proto_to_bosdyn_msgs_manipulator_state(proto.manipulator_state, ros_msg.manipulator_state) - ros_msg.manipulator_state_is_set = proto.HasField("manipulator_state") - convert_proto_to_bosdyn_msgs_service_fault_state(proto.service_fault_state, ros_msg.service_fault_state) - ros_msg.service_fault_state_is_set = proto.HasField("service_fault_state") - convert_proto_to_bosdyn_msgs_terrain_state(proto.terrain_state, ros_msg.terrain_state) - ros_msg.terrain_state_is_set = proto.HasField("terrain_state") - - -def convert_bosdyn_msgs_robot_state_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotState", proto: "bosdyn.api.robot_state_pb2.RobotState") -> None: - proto.Clear() - if ros_msg.power_state_is_set: - convert_bosdyn_msgs_power_state_to_proto(ros_msg.power_state, proto.power_state) - del proto.battery_states[:] - for _item in ros_msg.battery_states: - convert_bosdyn_msgs_battery_state_to_proto(_item, proto.battery_states.add()) - del proto.comms_states[:] - for _item in ros_msg.comms_states: - convert_bosdyn_msgs_comms_state_to_proto(_item, proto.comms_states.add()) - if ros_msg.system_fault_state_is_set: - convert_bosdyn_msgs_system_fault_state_to_proto(ros_msg.system_fault_state, proto.system_fault_state) - del proto.estop_states[:] - for _item in ros_msg.estop_states: - convert_bosdyn_msgs_e_stop_state_to_proto(_item, proto.estop_states.add()) - if ros_msg.kinematic_state_is_set: - convert_bosdyn_msgs_kinematic_state_to_proto(ros_msg.kinematic_state, proto.kinematic_state) - if ros_msg.behavior_fault_state_is_set: - convert_bosdyn_msgs_behavior_fault_state_to_proto(ros_msg.behavior_fault_state, proto.behavior_fault_state) - del proto.foot_state[:] - for _item in ros_msg.foot_state: - convert_bosdyn_msgs_foot_state_to_proto(_item, proto.foot_state.add()) - if ros_msg.manipulator_state_is_set: - convert_bosdyn_msgs_manipulator_state_to_proto(ros_msg.manipulator_state, proto.manipulator_state) - if ros_msg.service_fault_state_is_set: - convert_bosdyn_msgs_service_fault_state_to_proto(ros_msg.service_fault_state, proto.service_fault_state) - if ros_msg.terrain_state_is_set: - convert_bosdyn_msgs_terrain_state_to_proto(ros_msg.terrain_state, proto.terrain_state) - - -def convert_proto_to_bosdyn_msgs_power_state_motor_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState.MotorPowerState", ros_msg: "bosdyn_msgs.msgs.PowerStateMotorPowerState") -> None: - pass - - -def convert_bosdyn_msgs_power_state_motor_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStateMotorPowerState", proto: "bosdyn.api.robot_state_pb2.PowerState.MotorPowerState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_state_shore_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState.ShorePowerState", ros_msg: "bosdyn_msgs.msgs.PowerStateShorePowerState") -> None: - pass - - -def convert_bosdyn_msgs_power_state_shore_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStateShorePowerState", proto: "bosdyn.api.robot_state_pb2.PowerState.ShorePowerState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_state_robot_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState.RobotPowerState", ros_msg: "bosdyn_msgs.msgs.PowerStateRobotPowerState") -> None: - pass - - -def convert_bosdyn_msgs_power_state_robot_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStateRobotPowerState", proto: "bosdyn.api.robot_state_pb2.PowerState.RobotPowerState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_state_payload_ports_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState.PayloadPortsPowerState", ros_msg: "bosdyn_msgs.msgs.PowerStatePayloadPortsPowerState") -> None: - pass - - -def convert_bosdyn_msgs_power_state_payload_ports_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStatePayloadPortsPowerState", proto: "bosdyn.api.robot_state_pb2.PowerState.PayloadPortsPowerState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_state_wifi_radio_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState.WifiRadioPowerState", ros_msg: "bosdyn_msgs.msgs.PowerStateWifiRadioPowerState") -> None: - pass - - -def convert_bosdyn_msgs_power_state_wifi_radio_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStateWifiRadioPowerState", proto: "bosdyn.api.robot_state_pb2.PowerState.WifiRadioPowerState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_power_state(proto: "bosdyn.api.robot_state_pb2.PowerState", ros_msg: "bosdyn_msgs.msgs.PowerState") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.motor_power_state.value = proto.motor_power_state - ros_msg.shore_power_state.value = proto.shore_power_state - ros_msg.robot_power_state.value = proto.robot_power_state - ros_msg.payload_ports_power_state.value = proto.payload_ports_power_state - ros_msg.wifi_radio_power_state.value = proto.wifi_radio_power_state - ros_msg.locomotion_charge_percentage = proto.locomotion_charge_percentage.value - ros_msg.locomotion_charge_percentage_is_set = proto.HasField("locomotion_charge_percentage") - convert_proto_to_builtin_interfaces_duration(proto.locomotion_estimated_runtime, ros_msg.locomotion_estimated_runtime) - ros_msg.locomotion_estimated_runtime_is_set = proto.HasField("locomotion_estimated_runtime") - - -def convert_bosdyn_msgs_power_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerState", proto: "bosdyn.api.robot_state_pb2.PowerState") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.motor_power_state = ros_msg.motor_power_state.value - proto.shore_power_state = ros_msg.shore_power_state.value - proto.robot_power_state = ros_msg.robot_power_state.value - proto.payload_ports_power_state = ros_msg.payload_ports_power_state.value - proto.wifi_radio_power_state = ros_msg.wifi_radio_power_state.value - if ros_msg.locomotion_charge_percentage_is_set: - convert_float64_to_proto(ros_msg.locomotion_charge_percentage, proto.locomotion_charge_percentage) - if ros_msg.locomotion_estimated_runtime_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.locomotion_estimated_runtime, proto.locomotion_estimated_runtime) - - -def convert_proto_to_bosdyn_msgs_system_fault_state(proto: "bosdyn.api.robot_state_pb2.SystemFaultState", ros_msg: "bosdyn_msgs.msgs.SystemFaultState") -> None: - from bosdyn_msgs.msg import SystemFault - ros_msg.faults = [] - for _item in proto.faults: - ros_msg.faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.faults[-1]) - from bosdyn_msgs.msg import SystemFault - ros_msg.historical_faults = [] - for _item in proto.historical_faults: - ros_msg.historical_faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.historical_faults[-1]) - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsSystemFaultSeverity - ros_msg.aggregated = [] - for _item in proto.aggregated: - ros_msg.aggregated.append(KeyStringValueBosdynMsgsSystemFaultSeverity()) - ros_msg.aggregated[-1].key = _item - convert_proto_to_bosdyn_msgs_system_fault_severity(proto.aggregated[_item], ros_msg.aggregated[-1].value) - - -def convert_bosdyn_msgs_system_fault_state_to_proto(ros_msg: "bosdyn_msgs.msgs.SystemFaultState", proto: "bosdyn.api.robot_state_pb2.SystemFaultState") -> None: - proto.Clear() - del proto.faults[:] - for _item in ros_msg.faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.faults.add()) - del proto.historical_faults[:] - for _item in ros_msg.historical_faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.historical_faults.add()) - for _item in ros_msg.aggregated: - convert_bosdyn_msgs_system_fault_severity_to_proto(_item.value, proto.aggregated[_item.key]) - - -def convert_proto_to_bosdyn_msgs_system_fault_severity(proto: "bosdyn.api.robot_state_pb2.SystemFault.Severity", ros_msg: "bosdyn_msgs.msgs.SystemFaultSeverity") -> None: - pass - - -def convert_bosdyn_msgs_system_fault_severity_to_proto(ros_msg: "bosdyn_msgs.msgs.SystemFaultSeverity", proto: "bosdyn.api.robot_state_pb2.SystemFault.Severity") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_system_fault(proto: "bosdyn.api.robot_state_pb2.SystemFault", ros_msg: "bosdyn_msgs.msgs.SystemFault") -> None: - ros_msg.name = proto.name - convert_proto_to_builtin_interfaces_time(proto.onset_timestamp, ros_msg.onset_timestamp) - ros_msg.onset_timestamp_is_set = proto.HasField("onset_timestamp") - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - ros_msg.duration_is_set = proto.HasField("duration") - ros_msg.code = proto.code - ros_msg.uid = proto.uid - ros_msg.error_message = proto.error_message - ros_msg.attributes = [] - for _item in proto.attributes: - ros_msg.attributes.append(_item) - ros_msg.severity.value = proto.severity - - -def convert_bosdyn_msgs_system_fault_to_proto(ros_msg: "bosdyn_msgs.msgs.SystemFault", proto: "bosdyn.api.robot_state_pb2.SystemFault") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.onset_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.onset_timestamp, proto.onset_timestamp) - if ros_msg.duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - proto.code = ros_msg.code - proto.uid = ros_msg.uid - proto.error_message = ros_msg.error_message - del proto.attributes[:] - for _item in ros_msg.attributes: - proto.attributes.append(_item) - proto.severity = ros_msg.severity.value - - -def convert_proto_to_bosdyn_msgs_e_stop_state_type(proto: "bosdyn.api.robot_state_pb2.EStopState.Type", ros_msg: "bosdyn_msgs.msgs.EStopStateType") -> None: - pass - - -def convert_bosdyn_msgs_e_stop_state_type_to_proto(ros_msg: "bosdyn_msgs.msgs.EStopStateType", proto: "bosdyn.api.robot_state_pb2.EStopState.Type") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_e_stop_state_state(proto: "bosdyn.api.robot_state_pb2.EStopState.State", ros_msg: "bosdyn_msgs.msgs.EStopStateState") -> None: - pass - - -def convert_bosdyn_msgs_e_stop_state_state_to_proto(ros_msg: "bosdyn_msgs.msgs.EStopStateState", proto: "bosdyn.api.robot_state_pb2.EStopState.State") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_e_stop_state(proto: "bosdyn.api.robot_state_pb2.EStopState", ros_msg: "bosdyn_msgs.msgs.EStopState") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.name = proto.name - ros_msg.type.value = proto.type - ros_msg.state.value = proto.state - ros_msg.state_description = proto.state_description - - -def convert_bosdyn_msgs_e_stop_state_to_proto(ros_msg: "bosdyn_msgs.msgs.EStopState", proto: "bosdyn.api.robot_state_pb2.EStopState") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.name = ros_msg.name - proto.type = ros_msg.type.value - proto.state = ros_msg.state.value - proto.state_description = ros_msg.state_description - - -def convert_proto_to_bosdyn_msgs_battery_state_status(proto: "bosdyn.api.robot_state_pb2.BatteryState.Status", ros_msg: "bosdyn_msgs.msgs.BatteryStateStatus") -> None: - pass - - -def convert_bosdyn_msgs_battery_state_status_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryStateStatus", proto: "bosdyn.api.robot_state_pb2.BatteryState.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_battery_state(proto: "bosdyn.api.robot_state_pb2.BatteryState", ros_msg: "bosdyn_msgs.msgs.BatteryState") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - ros_msg.identifier = proto.identifier - ros_msg.charge_percentage = proto.charge_percentage.value - ros_msg.charge_percentage_is_set = proto.HasField("charge_percentage") - convert_proto_to_builtin_interfaces_duration(proto.estimated_runtime, ros_msg.estimated_runtime) - ros_msg.estimated_runtime_is_set = proto.HasField("estimated_runtime") - ros_msg.current = proto.current.value - ros_msg.current_is_set = proto.HasField("current") - ros_msg.voltage = proto.voltage.value - ros_msg.voltage_is_set = proto.HasField("voltage") - ros_msg.temperatures = [] - for _item in proto.temperatures: - ros_msg.temperatures.append(_item) - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_battery_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BatteryState", proto: "bosdyn.api.robot_state_pb2.BatteryState") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - proto.identifier = ros_msg.identifier - if ros_msg.charge_percentage_is_set: - convert_float64_to_proto(ros_msg.charge_percentage, proto.charge_percentage) - if ros_msg.estimated_runtime_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.estimated_runtime, proto.estimated_runtime) - if ros_msg.current_is_set: - convert_float64_to_proto(ros_msg.current, proto.current) - if ros_msg.voltage_is_set: - convert_float64_to_proto(ros_msg.voltage, proto.voltage) - del proto.temperatures[:] - for _item in ros_msg.temperatures: - proto.temperatures.append(_item) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_kinematic_state(proto: "bosdyn.api.robot_state_pb2.KinematicState", ros_msg: "bosdyn_msgs.msgs.KinematicState") -> None: - from bosdyn_msgs.msg import JointState - ros_msg.joint_states = [] - for _item in proto.joint_states: - ros_msg.joint_states.append(JointState()) - convert_proto_to_bosdyn_msgs_joint_state(_item, ros_msg.joint_states[-1]) - convert_proto_to_builtin_interfaces_time(proto.acquisition_timestamp, ros_msg.acquisition_timestamp) - ros_msg.acquisition_timestamp_is_set = proto.HasField("acquisition_timestamp") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - convert_proto_to_geometry_msgs_twist(proto.velocity_of_body_in_vision, ros_msg.velocity_of_body_in_vision) - ros_msg.velocity_of_body_in_vision_is_set = proto.HasField("velocity_of_body_in_vision") - convert_proto_to_geometry_msgs_twist(proto.velocity_of_body_in_odom, ros_msg.velocity_of_body_in_odom) - ros_msg.velocity_of_body_in_odom_is_set = proto.HasField("velocity_of_body_in_odom") - - -def convert_bosdyn_msgs_kinematic_state_to_proto(ros_msg: "bosdyn_msgs.msgs.KinematicState", proto: "bosdyn.api.robot_state_pb2.KinematicState") -> None: - proto.Clear() - del proto.joint_states[:] - for _item in ros_msg.joint_states: - convert_bosdyn_msgs_joint_state_to_proto(_item, proto.joint_states.add()) - if ros_msg.acquisition_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.acquisition_timestamp, proto.acquisition_timestamp) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - if ros_msg.velocity_of_body_in_vision_is_set: - convert_geometry_msgs_twist_to_proto(ros_msg.velocity_of_body_in_vision, proto.velocity_of_body_in_vision) - if ros_msg.velocity_of_body_in_odom_is_set: - convert_geometry_msgs_twist_to_proto(ros_msg.velocity_of_body_in_odom, proto.velocity_of_body_in_odom) - - -def convert_proto_to_bosdyn_msgs_joint_state(proto: "bosdyn.api.robot_state_pb2.JointState", ros_msg: "bosdyn_msgs.msgs.JointState") -> None: - ros_msg.name = proto.name - ros_msg.position = proto.position.value - ros_msg.position_is_set = proto.HasField("position") - ros_msg.velocity = proto.velocity.value - ros_msg.velocity_is_set = proto.HasField("velocity") - ros_msg.acceleration = proto.acceleration.value - ros_msg.acceleration_is_set = proto.HasField("acceleration") - ros_msg.load = proto.load.value - ros_msg.load_is_set = proto.HasField("load") - - -def convert_bosdyn_msgs_joint_state_to_proto(ros_msg: "bosdyn_msgs.msgs.JointState", proto: "bosdyn.api.robot_state_pb2.JointState") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.position_is_set: - convert_float64_to_proto(ros_msg.position, proto.position) - if ros_msg.velocity_is_set: - convert_float64_to_proto(ros_msg.velocity, proto.velocity) - if ros_msg.acceleration_is_set: - convert_float64_to_proto(ros_msg.acceleration, proto.acceleration) - if ros_msg.load_is_set: - convert_float64_to_proto(ros_msg.load, proto.load) - - -def convert_proto_to_bosdyn_msgs_behavior_fault_state(proto: "bosdyn.api.robot_state_pb2.BehaviorFaultState", ros_msg: "bosdyn_msgs.msgs.BehaviorFaultState") -> None: - from bosdyn_msgs.msg import BehaviorFault - ros_msg.faults = [] - for _item in proto.faults: - ros_msg.faults.append(BehaviorFault()) - convert_proto_to_bosdyn_msgs_behavior_fault(_item, ros_msg.faults[-1]) - - -def convert_bosdyn_msgs_behavior_fault_state_to_proto(ros_msg: "bosdyn_msgs.msgs.BehaviorFaultState", proto: "bosdyn.api.robot_state_pb2.BehaviorFaultState") -> None: - proto.Clear() - del proto.faults[:] - for _item in ros_msg.faults: - convert_bosdyn_msgs_behavior_fault_to_proto(_item, proto.faults.add()) - - -def convert_proto_to_bosdyn_msgs_behavior_fault_cause(proto: "bosdyn.api.robot_state_pb2.BehaviorFault.Cause", ros_msg: "bosdyn_msgs.msgs.BehaviorFaultCause") -> None: - pass - - -def convert_bosdyn_msgs_behavior_fault_cause_to_proto(ros_msg: "bosdyn_msgs.msgs.BehaviorFaultCause", proto: "bosdyn.api.robot_state_pb2.BehaviorFault.Cause") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_behavior_fault_status(proto: "bosdyn.api.robot_state_pb2.BehaviorFault.Status", ros_msg: "bosdyn_msgs.msgs.BehaviorFaultStatus") -> None: - pass - - -def convert_bosdyn_msgs_behavior_fault_status_to_proto(ros_msg: "bosdyn_msgs.msgs.BehaviorFaultStatus", proto: "bosdyn.api.robot_state_pb2.BehaviorFault.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_behavior_fault(proto: "bosdyn.api.robot_state_pb2.BehaviorFault", ros_msg: "bosdyn_msgs.msgs.BehaviorFault") -> None: - ros_msg.behavior_fault_id = proto.behavior_fault_id - convert_proto_to_builtin_interfaces_time(proto.onset_timestamp, ros_msg.onset_timestamp) - ros_msg.onset_timestamp_is_set = proto.HasField("onset_timestamp") - ros_msg.cause.value = proto.cause - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_behavior_fault_to_proto(ros_msg: "bosdyn_msgs.msgs.BehaviorFault", proto: "bosdyn.api.robot_state_pb2.BehaviorFault") -> None: - proto.Clear() - proto.behavior_fault_id = ros_msg.behavior_fault_id - if ros_msg.onset_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.onset_timestamp, proto.onset_timestamp) - proto.cause = ros_msg.cause.value - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_robot_metrics(proto: "bosdyn.api.robot_state_pb2.RobotMetrics", ros_msg: "bosdyn_msgs.msgs.RobotMetrics") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - from bosdyn_msgs.msg import Parameter - ros_msg.metrics = [] - for _item in proto.metrics: - ros_msg.metrics.append(Parameter()) - convert_proto_to_bosdyn_msgs_parameter(_item, ros_msg.metrics[-1]) - - -def convert_bosdyn_msgs_robot_metrics_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotMetrics", proto: "bosdyn.api.robot_state_pb2.RobotMetrics") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - del proto.metrics[:] - for _item in ros_msg.metrics: - convert_bosdyn_msgs_parameter_to_proto(_item, proto.metrics.add()) - - -def convert_proto_to_bosdyn_msgs_comms_state_one_of_state(proto: "bosdyn.api.robot_state_pb2.CommsState", ros_msg: "bosdyn_msgs.msgs.CommsStateOneOfState") -> None: - if proto.HasField("wifi_state"): - ros_msg.state_choice = ros_msg.STATE_WIFI_STATE_SET - convert_proto_to_bosdyn_msgs_wi_fi_state(proto.wifi_state, ros_msg.wifi_state) - - -def convert_bosdyn_msgs_comms_state_one_of_state_to_proto(ros_msg: "bosdyn_msgs.msgs.CommsStateOneOfState", proto: "bosdyn.api.robot_state_pb2.CommsState") -> None: - proto.ClearField("state") - if ros_msg.state_choice == ros_msg.STATE_WIFI_STATE_SET: - convert_bosdyn_msgs_wi_fi_state_to_proto(ros_msg.wifi_state, proto.wifi_state) - - -def convert_proto_to_bosdyn_msgs_comms_state(proto: "bosdyn.api.robot_state_pb2.CommsState", ros_msg: "bosdyn_msgs.msgs.CommsState") -> None: - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - convert_proto_to_bosdyn_msgs_comms_state_one_of_state(proto, ros_msg.state) - - -def convert_bosdyn_msgs_comms_state_to_proto(ros_msg: "bosdyn_msgs.msgs.CommsState", proto: "bosdyn.api.robot_state_pb2.CommsState") -> None: - proto.Clear() - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - convert_bosdyn_msgs_comms_state_one_of_state_to_proto(ros_msg.state, proto) - - -def convert_proto_to_bosdyn_msgs_wi_fi_state_mode(proto: "bosdyn.api.robot_state_pb2.WiFiState.Mode", ros_msg: "bosdyn_msgs.msgs.WiFiStateMode") -> None: - pass - - -def convert_bosdyn_msgs_wi_fi_state_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.WiFiStateMode", proto: "bosdyn.api.robot_state_pb2.WiFiState.Mode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_wi_fi_state(proto: "bosdyn.api.robot_state_pb2.WiFiState", ros_msg: "bosdyn_msgs.msgs.WiFiState") -> None: - ros_msg.current_mode.value = proto.current_mode - ros_msg.essid = proto.essid - - -def convert_bosdyn_msgs_wi_fi_state_to_proto(ros_msg: "bosdyn_msgs.msgs.WiFiState", proto: "bosdyn.api.robot_state_pb2.WiFiState") -> None: - proto.Clear() - proto.current_mode = ros_msg.current_mode.value - proto.essid = ros_msg.essid - - -def convert_proto_to_bosdyn_msgs_foot_state_contact(proto: "bosdyn.api.robot_state_pb2.FootState.Contact", ros_msg: "bosdyn_msgs.msgs.FootStateContact") -> None: - pass - - -def convert_bosdyn_msgs_foot_state_contact_to_proto(ros_msg: "bosdyn_msgs.msgs.FootStateContact", proto: "bosdyn.api.robot_state_pb2.FootState.Contact") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_foot_state_terrain_state(proto: "bosdyn.api.robot_state_pb2.FootState.TerrainState", ros_msg: "bosdyn_msgs.msgs.FootStateTerrainState") -> None: - ros_msg.ground_mu_est = proto.ground_mu_est - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.foot_slip_distance_rt_frame, ros_msg.foot_slip_distance_rt_frame) - ros_msg.foot_slip_distance_rt_frame_is_set = proto.HasField("foot_slip_distance_rt_frame") - convert_proto_to_geometry_msgs_vector3(proto.foot_slip_velocity_rt_frame, ros_msg.foot_slip_velocity_rt_frame) - ros_msg.foot_slip_velocity_rt_frame_is_set = proto.HasField("foot_slip_velocity_rt_frame") - convert_proto_to_geometry_msgs_vector3(proto.ground_contact_normal_rt_frame, ros_msg.ground_contact_normal_rt_frame) - ros_msg.ground_contact_normal_rt_frame_is_set = proto.HasField("ground_contact_normal_rt_frame") - ros_msg.visual_surface_ground_penetration_mean = proto.visual_surface_ground_penetration_mean - ros_msg.visual_surface_ground_penetration_std = proto.visual_surface_ground_penetration_std - - -def convert_bosdyn_msgs_foot_state_terrain_state_to_proto(ros_msg: "bosdyn_msgs.msgs.FootStateTerrainState", proto: "bosdyn.api.robot_state_pb2.FootState.TerrainState") -> None: - proto.Clear() - proto.ground_mu_est = ros_msg.ground_mu_est - proto.frame_name = ros_msg.frame_name - if ros_msg.foot_slip_distance_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.foot_slip_distance_rt_frame, proto.foot_slip_distance_rt_frame) - if ros_msg.foot_slip_velocity_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.foot_slip_velocity_rt_frame, proto.foot_slip_velocity_rt_frame) - if ros_msg.ground_contact_normal_rt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ground_contact_normal_rt_frame, proto.ground_contact_normal_rt_frame) - proto.visual_surface_ground_penetration_mean = ros_msg.visual_surface_ground_penetration_mean - proto.visual_surface_ground_penetration_std = ros_msg.visual_surface_ground_penetration_std - - -def convert_proto_to_bosdyn_msgs_foot_state(proto: "bosdyn.api.robot_state_pb2.FootState", ros_msg: "bosdyn_msgs.msgs.FootState") -> None: - convert_proto_to_geometry_msgs_vector3(proto.foot_position_rt_body, ros_msg.foot_position_rt_body) - ros_msg.foot_position_rt_body_is_set = proto.HasField("foot_position_rt_body") - ros_msg.contact.value = proto.contact - convert_proto_to_bosdyn_msgs_foot_state_terrain_state(proto.terrain, ros_msg.terrain) - ros_msg.terrain_is_set = proto.HasField("terrain") - - -def convert_bosdyn_msgs_foot_state_to_proto(ros_msg: "bosdyn_msgs.msgs.FootState", proto: "bosdyn.api.robot_state_pb2.FootState") -> None: - proto.Clear() - if ros_msg.foot_position_rt_body_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.foot_position_rt_body, proto.foot_position_rt_body) - proto.contact = ros_msg.contact.value - if ros_msg.terrain_is_set: - convert_bosdyn_msgs_foot_state_terrain_state_to_proto(ros_msg.terrain, proto.terrain) - - -def convert_proto_to_bosdyn_msgs_manipulator_state_stow_state(proto: "bosdyn.api.robot_state_pb2.ManipulatorState.StowState", ros_msg: "bosdyn_msgs.msgs.ManipulatorStateStowState") -> None: - pass - - -def convert_bosdyn_msgs_manipulator_state_stow_state_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulatorStateStowState", proto: "bosdyn.api.robot_state_pb2.ManipulatorState.StowState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_manipulator_state_carry_state(proto: "bosdyn.api.robot_state_pb2.ManipulatorState.CarryState", ros_msg: "bosdyn_msgs.msgs.ManipulatorStateCarryState") -> None: - pass - - -def convert_bosdyn_msgs_manipulator_state_carry_state_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulatorStateCarryState", proto: "bosdyn.api.robot_state_pb2.ManipulatorState.CarryState") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_manipulator_state(proto: "bosdyn.api.robot_state_pb2.ManipulatorState", ros_msg: "bosdyn_msgs.msgs.ManipulatorState") -> None: - ros_msg.gripper_open_percentage = proto.gripper_open_percentage - ros_msg.is_gripper_holding_item = proto.is_gripper_holding_item - convert_proto_to_geometry_msgs_vector3(proto.estimated_end_effector_force_in_hand, ros_msg.estimated_end_effector_force_in_hand) - ros_msg.estimated_end_effector_force_in_hand_is_set = proto.HasField("estimated_end_effector_force_in_hand") - ros_msg.stow_state.value = proto.stow_state - convert_proto_to_geometry_msgs_twist(proto.velocity_of_hand_in_vision, ros_msg.velocity_of_hand_in_vision) - ros_msg.velocity_of_hand_in_vision_is_set = proto.HasField("velocity_of_hand_in_vision") - convert_proto_to_geometry_msgs_twist(proto.velocity_of_hand_in_odom, ros_msg.velocity_of_hand_in_odom) - ros_msg.velocity_of_hand_in_odom_is_set = proto.HasField("velocity_of_hand_in_odom") - ros_msg.carry_state.value = proto.carry_state - - -def convert_bosdyn_msgs_manipulator_state_to_proto(ros_msg: "bosdyn_msgs.msgs.ManipulatorState", proto: "bosdyn.api.robot_state_pb2.ManipulatorState") -> None: - proto.Clear() - proto.gripper_open_percentage = ros_msg.gripper_open_percentage - proto.is_gripper_holding_item = ros_msg.is_gripper_holding_item - if ros_msg.estimated_end_effector_force_in_hand_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.estimated_end_effector_force_in_hand, proto.estimated_end_effector_force_in_hand) - proto.stow_state = ros_msg.stow_state.value - if ros_msg.velocity_of_hand_in_vision_is_set: - convert_geometry_msgs_twist_to_proto(ros_msg.velocity_of_hand_in_vision, proto.velocity_of_hand_in_vision) - if ros_msg.velocity_of_hand_in_odom_is_set: - convert_geometry_msgs_twist_to_proto(ros_msg.velocity_of_hand_in_odom, proto.velocity_of_hand_in_odom) - proto.carry_state = ros_msg.carry_state.value - - -def convert_proto_to_bosdyn_msgs_service_fault_state(proto: "bosdyn.api.robot_state_pb2.ServiceFaultState", ros_msg: "bosdyn_msgs.msgs.ServiceFaultState") -> None: - from bosdyn_msgs.msg import ServiceFault - ros_msg.faults = [] - for _item in proto.faults: - ros_msg.faults.append(ServiceFault()) - convert_proto_to_bosdyn_msgs_service_fault(_item, ros_msg.faults[-1]) - from bosdyn_msgs.msg import ServiceFault - ros_msg.historical_faults = [] - for _item in proto.historical_faults: - ros_msg.historical_faults.append(ServiceFault()) - convert_proto_to_bosdyn_msgs_service_fault(_item, ros_msg.historical_faults[-1]) - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsServiceFaultSeverity - ros_msg.aggregated = [] - for _item in proto.aggregated: - ros_msg.aggregated.append(KeyStringValueBosdynMsgsServiceFaultSeverity()) - ros_msg.aggregated[-1].key = _item - convert_proto_to_bosdyn_msgs_service_fault_severity(proto.aggregated[_item], ros_msg.aggregated[-1].value) - - -def convert_bosdyn_msgs_service_fault_state_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceFaultState", proto: "bosdyn.api.robot_state_pb2.ServiceFaultState") -> None: - proto.Clear() - del proto.faults[:] - for _item in ros_msg.faults: - convert_bosdyn_msgs_service_fault_to_proto(_item, proto.faults.add()) - del proto.historical_faults[:] - for _item in ros_msg.historical_faults: - convert_bosdyn_msgs_service_fault_to_proto(_item, proto.historical_faults.add()) - for _item in ros_msg.aggregated: - convert_bosdyn_msgs_service_fault_severity_to_proto(_item.value, proto.aggregated[_item.key]) - - -def convert_proto_to_bosdyn_msgs_terrain_state(proto: "bosdyn.api.robot_state_pb2.TerrainState", ros_msg: "bosdyn_msgs.msgs.TerrainState") -> None: - ros_msg.is_unsafe_to_sit = proto.is_unsafe_to_sit - - -def convert_bosdyn_msgs_terrain_state_to_proto(ros_msg: "bosdyn_msgs.msgs.TerrainState", proto: "bosdyn.api.robot_state_pb2.TerrainState") -> None: - proto.Clear() - proto.is_unsafe_to_sit = ros_msg.is_unsafe_to_sit - - -def convert_proto_to_bosdyn_msgs_robot_state_request(proto: "bosdyn.api.robot_state_pb2.RobotStateRequest", ros_msg: "bosdyn_msgs.msgs.RobotStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_robot_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotStateRequest", proto: "bosdyn.api.robot_state_pb2.RobotStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_robot_state_response(proto: "bosdyn.api.robot_state_pb2.RobotStateResponse", ros_msg: "bosdyn_msgs.msgs.RobotStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_robot_state(proto.robot_state, ros_msg.robot_state) - ros_msg.robot_state_is_set = proto.HasField("robot_state") - - -def convert_bosdyn_msgs_robot_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotStateResponse", proto: "bosdyn.api.robot_state_pb2.RobotStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.robot_state_is_set: - convert_bosdyn_msgs_robot_state_to_proto(ros_msg.robot_state, proto.robot_state) - - -def convert_proto_to_bosdyn_msgs_robot_metrics_request(proto: "bosdyn.api.robot_state_pb2.RobotMetricsRequest", ros_msg: "bosdyn_msgs.msgs.RobotMetricsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_robot_metrics_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotMetricsRequest", proto: "bosdyn.api.robot_state_pb2.RobotMetricsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_robot_metrics_response(proto: "bosdyn.api.robot_state_pb2.RobotMetricsResponse", ros_msg: "bosdyn_msgs.msgs.RobotMetricsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_robot_metrics(proto.robot_metrics, ros_msg.robot_metrics) - ros_msg.robot_metrics_is_set = proto.HasField("robot_metrics") - - -def convert_bosdyn_msgs_robot_metrics_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotMetricsResponse", proto: "bosdyn.api.robot_state_pb2.RobotMetricsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.robot_metrics_is_set: - convert_bosdyn_msgs_robot_metrics_to_proto(ros_msg.robot_metrics, proto.robot_metrics) - - -def convert_proto_to_bosdyn_msgs_robot_hardware_configuration_request(proto: "bosdyn.api.robot_state_pb2.RobotHardwareConfigurationRequest", ros_msg: "bosdyn_msgs.msgs.RobotHardwareConfigurationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_robot_hardware_configuration_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotHardwareConfigurationRequest", proto: "bosdyn.api.robot_state_pb2.RobotHardwareConfigurationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_robot_hardware_configuration_response(proto: "bosdyn.api.robot_state_pb2.RobotHardwareConfigurationResponse", ros_msg: "bosdyn_msgs.msgs.RobotHardwareConfigurationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_hardware_configuration(proto.hardware_configuration, ros_msg.hardware_configuration) - ros_msg.hardware_configuration_is_set = proto.HasField("hardware_configuration") - - -def convert_bosdyn_msgs_robot_hardware_configuration_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotHardwareConfigurationResponse", proto: "bosdyn.api.robot_state_pb2.RobotHardwareConfigurationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.hardware_configuration_is_set: - convert_bosdyn_msgs_hardware_configuration_to_proto(ros_msg.hardware_configuration, proto.hardware_configuration) - - -def convert_proto_to_bosdyn_msgs_robot_link_model_request(proto: "bosdyn.api.robot_state_pb2.RobotLinkModelRequest", ros_msg: "bosdyn_msgs.msgs.RobotLinkModelRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.link_name = proto.link_name - - -def convert_bosdyn_msgs_robot_link_model_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotLinkModelRequest", proto: "bosdyn.api.robot_state_pb2.RobotLinkModelRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.link_name = ros_msg.link_name - - -def convert_proto_to_bosdyn_msgs_robot_link_model_response(proto: "bosdyn.api.robot_state_pb2.RobotLinkModelResponse", ros_msg: "bosdyn_msgs.msgs.RobotLinkModelResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_skeleton_link_obj_model(proto.link_model, ros_msg.link_model) - ros_msg.link_model_is_set = proto.HasField("link_model") - - -def convert_bosdyn_msgs_robot_link_model_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotLinkModelResponse", proto: "bosdyn.api.robot_state_pb2.RobotLinkModelResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.link_model_is_set: - convert_bosdyn_msgs_skeleton_link_obj_model_to_proto(ros_msg.link_model, proto.link_model) - - -def convert_proto_to_bosdyn_msgs_robot_impaired_state_impaired_status(proto: "bosdyn.api.robot_state_pb2.RobotImpairedState.ImpairedStatus", ros_msg: "bosdyn_msgs.msgs.RobotImpairedStateImpairedStatus") -> None: - pass - - -def convert_bosdyn_msgs_robot_impaired_state_impaired_status_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotImpairedStateImpairedStatus", proto: "bosdyn.api.robot_state_pb2.RobotImpairedState.ImpairedStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_robot_impaired_state(proto: "bosdyn.api.robot_state_pb2.RobotImpairedState", ros_msg: "bosdyn_msgs.msgs.RobotImpairedState") -> None: - ros_msg.impaired_status.value = proto.impaired_status - from bosdyn_msgs.msg import SystemFault - ros_msg.system_faults = [] - for _item in proto.system_faults: - ros_msg.system_faults.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.system_faults[-1]) - from bosdyn_msgs.msg import ServiceFault - ros_msg.service_faults = [] - for _item in proto.service_faults: - ros_msg.service_faults.append(ServiceFault()) - convert_proto_to_bosdyn_msgs_service_fault(_item, ros_msg.service_faults[-1]) - from bosdyn_msgs.msg import BehaviorFault - ros_msg.behavior_faults = [] - for _item in proto.behavior_faults: - ros_msg.behavior_faults.append(BehaviorFault()) - convert_proto_to_bosdyn_msgs_behavior_fault(_item, ros_msg.behavior_faults[-1]) - - -def convert_bosdyn_msgs_robot_impaired_state_to_proto(ros_msg: "bosdyn_msgs.msgs.RobotImpairedState", proto: "bosdyn.api.robot_state_pb2.RobotImpairedState") -> None: - proto.Clear() - proto.impaired_status = ros_msg.impaired_status.value - del proto.system_faults[:] - for _item in ros_msg.system_faults: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.system_faults.add()) - del proto.service_faults[:] - for _item in ros_msg.service_faults: - convert_bosdyn_msgs_service_fault_to_proto(_item, proto.service_faults.add()) - del proto.behavior_faults[:] - for _item in ros_msg.behavior_faults: - convert_bosdyn_msgs_behavior_fault_to_proto(_item, proto.behavior_faults.add()) - - -def convert_proto_to_bosdyn_msgs_custom_param_spec_one_of_spec(proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec", ros_msg: "bosdyn_msgs.msgs.CustomParamSpecOneOfSpec") -> None: - if proto.HasField("dict_spec"): - ros_msg.spec_choice = ros_msg.SPEC_DICT_SPEC_SET - convert_proto_to_serialized_bosdyn_msgs_dict_param_spec(proto.dict_spec, ros_msg.dict_spec) - if proto.HasField("list_spec"): - ros_msg.spec_choice = ros_msg.SPEC_LIST_SPEC_SET - convert_proto_to_bosdyn_msgs_list_param_spec(proto.list_spec, ros_msg.list_spec) - if proto.HasField("int_spec"): - ros_msg.spec_choice = ros_msg.SPEC_INT_SPEC_SET - convert_proto_to_bosdyn_msgs_int64_param_spec(proto.int_spec, ros_msg.int_spec) - if proto.HasField("double_spec"): - ros_msg.spec_choice = ros_msg.SPEC_DOUBLE_SPEC_SET - convert_proto_to_bosdyn_msgs_double_param_spec(proto.double_spec, ros_msg.double_spec) - if proto.HasField("string_spec"): - ros_msg.spec_choice = ros_msg.SPEC_STRING_SPEC_SET - convert_proto_to_bosdyn_msgs_string_param_spec(proto.string_spec, ros_msg.string_spec) - if proto.HasField("roi_spec"): - ros_msg.spec_choice = ros_msg.SPEC_ROI_SPEC_SET - convert_proto_to_bosdyn_msgs_region_of_interest_param_spec(proto.roi_spec, ros_msg.roi_spec) - if proto.HasField("bool_spec"): - ros_msg.spec_choice = ros_msg.SPEC_BOOL_SPEC_SET - convert_proto_to_bosdyn_msgs_bool_param_spec(proto.bool_spec, ros_msg.bool_spec) - if proto.HasField("one_of_spec"): - ros_msg.spec_choice = ros_msg.SPEC_ONE_OF_SPEC_SET - convert_proto_to_bosdyn_msgs_one_of_param_spec(proto.one_of_spec, ros_msg.one_of_spec) - - -def convert_bosdyn_msgs_custom_param_spec_one_of_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamSpecOneOfSpec", proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec") -> None: - proto.ClearField("spec") - if ros_msg.spec_choice == ros_msg.SPEC_DICT_SPEC_SET: - convert_serialized_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.dict_spec, proto.dict_spec) - if ros_msg.spec_choice == ros_msg.SPEC_LIST_SPEC_SET: - convert_bosdyn_msgs_list_param_spec_to_proto(ros_msg.list_spec, proto.list_spec) - if ros_msg.spec_choice == ros_msg.SPEC_INT_SPEC_SET: - convert_bosdyn_msgs_int64_param_spec_to_proto(ros_msg.int_spec, proto.int_spec) - if ros_msg.spec_choice == ros_msg.SPEC_DOUBLE_SPEC_SET: - convert_bosdyn_msgs_double_param_spec_to_proto(ros_msg.double_spec, proto.double_spec) - if ros_msg.spec_choice == ros_msg.SPEC_STRING_SPEC_SET: - convert_bosdyn_msgs_string_param_spec_to_proto(ros_msg.string_spec, proto.string_spec) - if ros_msg.spec_choice == ros_msg.SPEC_ROI_SPEC_SET: - convert_bosdyn_msgs_region_of_interest_param_spec_to_proto(ros_msg.roi_spec, proto.roi_spec) - if ros_msg.spec_choice == ros_msg.SPEC_BOOL_SPEC_SET: - convert_bosdyn_msgs_bool_param_spec_to_proto(ros_msg.bool_spec, proto.bool_spec) - if ros_msg.spec_choice == ros_msg.SPEC_ONE_OF_SPEC_SET: - convert_bosdyn_msgs_one_of_param_spec_to_proto(ros_msg.one_of_spec, proto.one_of_spec) - - -def convert_proto_to_bosdyn_msgs_custom_param_spec(proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec", ros_msg: "bosdyn_msgs.msgs.CustomParamSpec") -> None: - convert_proto_to_bosdyn_msgs_custom_param_spec_one_of_spec(proto, ros_msg.spec) - - -def convert_bosdyn_msgs_custom_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamSpec", proto: "bosdyn.api.service_customization_pb2.CustomParam.Spec") -> None: - proto.Clear() - convert_bosdyn_msgs_custom_param_spec_one_of_spec_to_proto(ros_msg.spec, proto) - - -def convert_proto_to_bosdyn_msgs_custom_param_one_of_value(proto: "bosdyn.api.service_customization_pb2.CustomParam", ros_msg: "bosdyn_msgs.msgs.CustomParamOneOfValue") -> None: - if proto.HasField("dict_value"): - ros_msg.value_choice = ros_msg.VALUE_DICT_VALUE_SET - convert_proto_to_serialized_bosdyn_msgs_dict_param(proto.dict_value, ros_msg.dict_value) - if proto.HasField("list_value"): - ros_msg.value_choice = ros_msg.VALUE_LIST_VALUE_SET - convert_proto_to_bosdyn_msgs_list_param(proto.list_value, ros_msg.list_value) - if proto.HasField("int_value"): - ros_msg.value_choice = ros_msg.VALUE_INT_VALUE_SET - convert_proto_to_bosdyn_msgs_int64_param(proto.int_value, ros_msg.int_value) - if proto.HasField("double_value"): - ros_msg.value_choice = ros_msg.VALUE_DOUBLE_VALUE_SET - convert_proto_to_bosdyn_msgs_double_param(proto.double_value, ros_msg.double_value) - if proto.HasField("string_value"): - ros_msg.value_choice = ros_msg.VALUE_STRING_VALUE_SET - convert_proto_to_bosdyn_msgs_string_param(proto.string_value, ros_msg.string_value) - if proto.HasField("roi_value"): - ros_msg.value_choice = ros_msg.VALUE_ROI_VALUE_SET - convert_proto_to_bosdyn_msgs_region_of_interest_param(proto.roi_value, ros_msg.roi_value) - if proto.HasField("bool_value"): - ros_msg.value_choice = ros_msg.VALUE_BOOL_VALUE_SET - convert_proto_to_bosdyn_msgs_bool_param(proto.bool_value, ros_msg.bool_value) - if proto.HasField("one_of_value"): - ros_msg.value_choice = ros_msg.VALUE_ONE_OF_VALUE_SET - convert_proto_to_bosdyn_msgs_one_of_param(proto.one_of_value, ros_msg.one_of_value) - - -def convert_bosdyn_msgs_custom_param_one_of_value_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamOneOfValue", proto: "bosdyn.api.service_customization_pb2.CustomParam") -> None: - proto.ClearField("value") - if ros_msg.value_choice == ros_msg.VALUE_DICT_VALUE_SET: - convert_serialized_bosdyn_msgs_dict_param_to_proto(ros_msg.dict_value, proto.dict_value) - if ros_msg.value_choice == ros_msg.VALUE_LIST_VALUE_SET: - convert_bosdyn_msgs_list_param_to_proto(ros_msg.list_value, proto.list_value) - if ros_msg.value_choice == ros_msg.VALUE_INT_VALUE_SET: - convert_bosdyn_msgs_int64_param_to_proto(ros_msg.int_value, proto.int_value) - if ros_msg.value_choice == ros_msg.VALUE_DOUBLE_VALUE_SET: - convert_bosdyn_msgs_double_param_to_proto(ros_msg.double_value, proto.double_value) - if ros_msg.value_choice == ros_msg.VALUE_STRING_VALUE_SET: - convert_bosdyn_msgs_string_param_to_proto(ros_msg.string_value, proto.string_value) - if ros_msg.value_choice == ros_msg.VALUE_ROI_VALUE_SET: - convert_bosdyn_msgs_region_of_interest_param_to_proto(ros_msg.roi_value, proto.roi_value) - if ros_msg.value_choice == ros_msg.VALUE_BOOL_VALUE_SET: - convert_bosdyn_msgs_bool_param_to_proto(ros_msg.bool_value, proto.bool_value) - if ros_msg.value_choice == ros_msg.VALUE_ONE_OF_VALUE_SET: - convert_bosdyn_msgs_one_of_param_to_proto(ros_msg.one_of_value, proto.one_of_value) - - -def convert_proto_to_bosdyn_msgs_custom_param(proto: "bosdyn.api.service_customization_pb2.CustomParam", ros_msg: "bosdyn_msgs.msgs.CustomParam") -> None: - convert_proto_to_bosdyn_msgs_custom_param_one_of_value(proto, ros_msg.value) - - -def convert_bosdyn_msgs_custom_param_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParam", proto: "bosdyn.api.service_customization_pb2.CustomParam") -> None: - proto.Clear() - convert_bosdyn_msgs_custom_param_one_of_value_to_proto(ros_msg.value, proto) - - -def convert_proto_to_bosdyn_msgs_user_interface_info(proto: "bosdyn.api.service_customization_pb2.UserInterfaceInfo", ros_msg: "bosdyn_msgs.msgs.UserInterfaceInfo") -> None: - ros_msg.display_name = proto.display_name - ros_msg.description = proto.description - ros_msg.display_order = proto.display_order - - -def convert_bosdyn_msgs_user_interface_info_to_proto(ros_msg: "bosdyn_msgs.msgs.UserInterfaceInfo", proto: "bosdyn.api.service_customization_pb2.UserInterfaceInfo") -> None: - proto.Clear() - proto.display_name = ros_msg.display_name - proto.description = ros_msg.description - proto.display_order = ros_msg.display_order - - -def convert_proto_to_bosdyn_msgs_custom_param_collection(proto: "bosdyn.api.service_customization_pb2.CustomParamCollection", ros_msg: "bosdyn_msgs.msgs.CustomParamCollection") -> None: - convert_proto_to_bosdyn_msgs_dict_param_spec(proto.specs, ros_msg.specs) - ros_msg.specs_is_set = proto.HasField("specs") - convert_proto_to_bosdyn_msgs_dict_param(proto.values, ros_msg.values) - ros_msg.values_is_set = proto.HasField("values") - - -def convert_bosdyn_msgs_custom_param_collection_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamCollection", proto: "bosdyn.api.service_customization_pb2.CustomParamCollection") -> None: - proto.Clear() - if ros_msg.specs_is_set: - convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.specs, proto.specs) - if ros_msg.values_is_set: - convert_bosdyn_msgs_dict_param_to_proto(ros_msg.values, proto.values) - - -def convert_proto_to_bosdyn_msgs_dict_param_child_spec(proto: "bosdyn.api.service_customization_pb2.DictParam.ChildSpec", ros_msg: "bosdyn_msgs.msgs.DictParamChildSpec") -> None: - convert_proto_to_bosdyn_msgs_custom_param_spec(proto.spec, ros_msg.spec) - ros_msg.spec_is_set = proto.HasField("spec") - convert_proto_to_bosdyn_msgs_user_interface_info(proto.ui_info, ros_msg.ui_info) - ros_msg.ui_info_is_set = proto.HasField("ui_info") - - -def convert_bosdyn_msgs_dict_param_child_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.DictParamChildSpec", proto: "bosdyn.api.service_customization_pb2.DictParam.ChildSpec") -> None: - proto.Clear() - if ros_msg.spec_is_set: - convert_bosdyn_msgs_custom_param_spec_to_proto(ros_msg.spec, proto.spec) - if ros_msg.ui_info_is_set: - convert_bosdyn_msgs_user_interface_info_to_proto(ros_msg.ui_info, proto.ui_info) - - -def convert_proto_to_bosdyn_msgs_dict_param_spec(proto: "bosdyn.api.service_customization_pb2.DictParam.Spec", ros_msg: "bosdyn_msgs.msgs.DictParamSpec") -> None: - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsDictParamChildSpec - ros_msg.specs = [] - for _item in proto.specs: - ros_msg.specs.append(KeyStringValueBosdynMsgsDictParamChildSpec()) - ros_msg.specs[-1].key = _item - convert_proto_to_bosdyn_msgs_dict_param_child_spec(proto.specs[_item], ros_msg.specs[-1].value) - ros_msg.is_hidden_by_default = proto.is_hidden_by_default - - -def convert_bosdyn_msgs_dict_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.DictParamSpec", proto: "bosdyn.api.service_customization_pb2.DictParam.Spec") -> None: - proto.Clear() - for _item in ros_msg.specs: - convert_bosdyn_msgs_dict_param_child_spec_to_proto(_item.value, proto.specs[_item.key]) - proto.is_hidden_by_default = ros_msg.is_hidden_by_default - - -def convert_proto_to_bosdyn_msgs_dict_param(proto: "bosdyn.api.service_customization_pb2.DictParam", ros_msg: "bosdyn_msgs.msgs.DictParam") -> None: - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsCustomParam - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(KeyStringValueBosdynMsgsCustomParam()) - ros_msg.values[-1].key = _item - convert_proto_to_bosdyn_msgs_custom_param(proto.values[_item], ros_msg.values[-1].value) - - -def convert_bosdyn_msgs_dict_param_to_proto(ros_msg: "bosdyn_msgs.msgs.DictParam", proto: "bosdyn.api.service_customization_pb2.DictParam") -> None: - proto.Clear() - for _item in ros_msg.values: - convert_bosdyn_msgs_custom_param_to_proto(_item.value, proto.values[_item.key]) - - -def convert_proto_to_bosdyn_msgs_one_of_param_child_spec(proto: "bosdyn.api.service_customization_pb2.OneOfParam.ChildSpec", ros_msg: "bosdyn_msgs.msgs.OneOfParamChildSpec") -> None: - convert_proto_to_serialized_bosdyn_msgs_dict_param_spec(proto.spec, ros_msg.spec) - ros_msg.spec_is_set = proto.HasField("spec") - convert_proto_to_bosdyn_msgs_user_interface_info(proto.ui_info, ros_msg.ui_info) - ros_msg.ui_info_is_set = proto.HasField("ui_info") - - -def convert_bosdyn_msgs_one_of_param_child_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.OneOfParamChildSpec", proto: "bosdyn.api.service_customization_pb2.OneOfParam.ChildSpec") -> None: - proto.Clear() - if ros_msg.spec_is_set: - convert_serialized_bosdyn_msgs_dict_param_spec_to_proto(ros_msg.spec, proto.spec) - if ros_msg.ui_info_is_set: - convert_bosdyn_msgs_user_interface_info_to_proto(ros_msg.ui_info, proto.ui_info) - - -def convert_proto_to_bosdyn_msgs_one_of_param_spec(proto: "bosdyn.api.service_customization_pb2.OneOfParam.Spec", ros_msg: "bosdyn_msgs.msgs.OneOfParamSpec") -> None: - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsOneOfParamChildSpec - ros_msg.specs = [] - for _item in proto.specs: - ros_msg.specs.append(KeyStringValueBosdynMsgsOneOfParamChildSpec()) - ros_msg.specs[-1].key = _item - convert_proto_to_bosdyn_msgs_one_of_param_child_spec(proto.specs[_item], ros_msg.specs[-1].value) - ros_msg.default_key = proto.default_key - - -def convert_bosdyn_msgs_one_of_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.OneOfParamSpec", proto: "bosdyn.api.service_customization_pb2.OneOfParam.Spec") -> None: - proto.Clear() - for _item in ros_msg.specs: - convert_bosdyn_msgs_one_of_param_child_spec_to_proto(_item.value, proto.specs[_item.key]) - proto.default_key = ros_msg.default_key - - -def convert_proto_to_bosdyn_msgs_one_of_param(proto: "bosdyn.api.service_customization_pb2.OneOfParam", ros_msg: "bosdyn_msgs.msgs.OneOfParam") -> None: - ros_msg.key = proto.key - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsSerializedMessage - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(KeyStringValueBosdynMsgsSerializedMessage()) - ros_msg.values[-1].key = _item - convert_proto_to_bosdyn_msgs_dict_param(proto.values[_item], ros_msg.values[-1].value) - - -def convert_bosdyn_msgs_one_of_param_to_proto(ros_msg: "bosdyn_msgs.msgs.OneOfParam", proto: "bosdyn.api.service_customization_pb2.OneOfParam") -> None: - proto.Clear() - proto.key = ros_msg.key - for _item in ros_msg.values: - convert_bosdyn_msgs_dict_param_to_proto(_item.value, proto.values[_item.key]) - - -def convert_proto_to_bosdyn_msgs_list_param_spec(proto: "bosdyn.api.service_customization_pb2.ListParam.Spec", ros_msg: "bosdyn_msgs.msgs.ListParamSpec") -> None: - convert_proto_to_serialized_bosdyn_msgs_custom_param_spec(proto.element_spec, ros_msg.element_spec) - ros_msg.element_spec_is_set = proto.HasField("element_spec") - ros_msg.min_number_of_values = proto.min_number_of_values.value - ros_msg.min_number_of_values_is_set = proto.HasField("min_number_of_values") - ros_msg.max_number_of_values = proto.max_number_of_values.value - ros_msg.max_number_of_values_is_set = proto.HasField("max_number_of_values") - - -def convert_bosdyn_msgs_list_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.ListParamSpec", proto: "bosdyn.api.service_customization_pb2.ListParam.Spec") -> None: - proto.Clear() - if ros_msg.element_spec_is_set: - convert_serialized_bosdyn_msgs_custom_param_spec_to_proto(ros_msg.element_spec, proto.element_spec) - if ros_msg.min_number_of_values_is_set: - convert_int64_to_proto(ros_msg.min_number_of_values, proto.min_number_of_values) - if ros_msg.max_number_of_values_is_set: - convert_int64_to_proto(ros_msg.max_number_of_values, proto.max_number_of_values) - - -def convert_proto_to_bosdyn_msgs_list_param(proto: "bosdyn.api.service_customization_pb2.ListParam", ros_msg: "bosdyn_msgs.msgs.ListParam") -> None: - from bosdyn_msgs.msg import SerializedMessage - ros_msg.values = [] - for _item in proto.values: - ros_msg.values.append(SerializedMessage()) - convert_proto_to_serialized_bosdyn_msgs_custom_param(_item, ros_msg.values[-1]) - - -def convert_bosdyn_msgs_list_param_to_proto(ros_msg: "bosdyn_msgs.msgs.ListParam", proto: "bosdyn.api.service_customization_pb2.ListParam") -> None: - proto.Clear() - del proto.values[:] - for _item in ros_msg.values: - convert_serialized_bosdyn_msgs_custom_param_to_proto(_item, proto.values.add()) - - -def convert_proto_to_bosdyn_msgs_int64_param_spec(proto: "bosdyn.api.service_customization_pb2.Int64Param.Spec", ros_msg: "bosdyn_msgs.msgs.Int64ParamSpec") -> None: - ros_msg.default_value = proto.default_value.value - ros_msg.default_value_is_set = proto.HasField("default_value") - convert_proto_to_bosdyn_msgs_units(proto.units, ros_msg.units) - ros_msg.units_is_set = proto.HasField("units") - ros_msg.min_value = proto.min_value.value - ros_msg.min_value_is_set = proto.HasField("min_value") - ros_msg.max_value = proto.max_value.value - ros_msg.max_value_is_set = proto.HasField("max_value") - - -def convert_bosdyn_msgs_int64_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.Int64ParamSpec", proto: "bosdyn.api.service_customization_pb2.Int64Param.Spec") -> None: - proto.Clear() - if ros_msg.default_value_is_set: - convert_int64_to_proto(ros_msg.default_value, proto.default_value) - if ros_msg.units_is_set: - convert_bosdyn_msgs_units_to_proto(ros_msg.units, proto.units) - if ros_msg.min_value_is_set: - convert_int64_to_proto(ros_msg.min_value, proto.min_value) - if ros_msg.max_value_is_set: - convert_int64_to_proto(ros_msg.max_value, proto.max_value) - - -def convert_proto_to_bosdyn_msgs_int64_param(proto: "bosdyn.api.service_customization_pb2.Int64Param", ros_msg: "bosdyn_msgs.msgs.Int64Param") -> None: - ros_msg.value = proto.value - - -def convert_bosdyn_msgs_int64_param_to_proto(ros_msg: "bosdyn_msgs.msgs.Int64Param", proto: "bosdyn.api.service_customization_pb2.Int64Param") -> None: - proto.Clear() - proto.value = ros_msg.value - - -def convert_proto_to_bosdyn_msgs_double_param_spec(proto: "bosdyn.api.service_customization_pb2.DoubleParam.Spec", ros_msg: "bosdyn_msgs.msgs.DoubleParamSpec") -> None: - ros_msg.default_value = proto.default_value.value - ros_msg.default_value_is_set = proto.HasField("default_value") - convert_proto_to_bosdyn_msgs_units(proto.units, ros_msg.units) - ros_msg.units_is_set = proto.HasField("units") - ros_msg.min_value = proto.min_value.value - ros_msg.min_value_is_set = proto.HasField("min_value") - ros_msg.max_value = proto.max_value.value - ros_msg.max_value_is_set = proto.HasField("max_value") - - -def convert_bosdyn_msgs_double_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.DoubleParamSpec", proto: "bosdyn.api.service_customization_pb2.DoubleParam.Spec") -> None: - proto.Clear() - if ros_msg.default_value_is_set: - convert_float64_to_proto(ros_msg.default_value, proto.default_value) - if ros_msg.units_is_set: - convert_bosdyn_msgs_units_to_proto(ros_msg.units, proto.units) - if ros_msg.min_value_is_set: - convert_float64_to_proto(ros_msg.min_value, proto.min_value) - if ros_msg.max_value_is_set: - convert_float64_to_proto(ros_msg.max_value, proto.max_value) - - -def convert_proto_to_bosdyn_msgs_double_param(proto: "bosdyn.api.service_customization_pb2.DoubleParam", ros_msg: "bosdyn_msgs.msgs.DoubleParam") -> None: - ros_msg.value = proto.value - - -def convert_bosdyn_msgs_double_param_to_proto(ros_msg: "bosdyn_msgs.msgs.DoubleParam", proto: "bosdyn.api.service_customization_pb2.DoubleParam") -> None: - proto.Clear() - proto.value = ros_msg.value - - -def convert_proto_to_bosdyn_msgs_string_param_spec(proto: "bosdyn.api.service_customization_pb2.StringParam.Spec", ros_msg: "bosdyn_msgs.msgs.StringParamSpec") -> None: - ros_msg.options = [] - for _item in proto.options: - ros_msg.options.append(_item) - ros_msg.editable = proto.editable - ros_msg.default_value = proto.default_value - - -def convert_bosdyn_msgs_string_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.StringParamSpec", proto: "bosdyn.api.service_customization_pb2.StringParam.Spec") -> None: - proto.Clear() - del proto.options[:] - for _item in ros_msg.options: - proto.options.append(_item) - proto.editable = ros_msg.editable - proto.default_value = ros_msg.default_value - - -def convert_proto_to_bosdyn_msgs_string_param(proto: "bosdyn.api.service_customization_pb2.StringParam", ros_msg: "bosdyn_msgs.msgs.StringParam") -> None: - ros_msg.value = proto.value - - -def convert_bosdyn_msgs_string_param_to_proto(ros_msg: "bosdyn_msgs.msgs.StringParam", proto: "bosdyn.api.service_customization_pb2.StringParam") -> None: - proto.Clear() - proto.value = ros_msg.value - - -def convert_proto_to_bosdyn_msgs_bool_param_spec(proto: "bosdyn.api.service_customization_pb2.BoolParam.Spec", ros_msg: "bosdyn_msgs.msgs.BoolParamSpec") -> None: - ros_msg.default_value = proto.default_value.value - ros_msg.default_value_is_set = proto.HasField("default_value") - - -def convert_bosdyn_msgs_bool_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.BoolParamSpec", proto: "bosdyn.api.service_customization_pb2.BoolParam.Spec") -> None: - proto.Clear() - if ros_msg.default_value_is_set: - convert_bool_to_proto(ros_msg.default_value, proto.default_value) - - -def convert_proto_to_bosdyn_msgs_bool_param(proto: "bosdyn.api.service_customization_pb2.BoolParam", ros_msg: "bosdyn_msgs.msgs.BoolParam") -> None: - ros_msg.value = proto.value - - -def convert_bosdyn_msgs_bool_param_to_proto(ros_msg: "bosdyn_msgs.msgs.BoolParam", proto: "bosdyn.api.service_customization_pb2.BoolParam") -> None: - proto.Clear() - proto.value = ros_msg.value - - -def convert_proto_to_bosdyn_msgs_region_of_interest_param_service_and_source(proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam.ServiceAndSource", ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParamServiceAndSource") -> None: - ros_msg.service = proto.service - ros_msg.source = proto.source - - -def convert_bosdyn_msgs_region_of_interest_param_service_and_source_to_proto(ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParamServiceAndSource", proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam.ServiceAndSource") -> None: - proto.Clear() - proto.service = ros_msg.service - proto.source = ros_msg.source - - -def convert_proto_to_bosdyn_msgs_region_of_interest_param_spec(proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam.Spec", ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParamSpec") -> None: - convert_proto_to_bosdyn_msgs_region_of_interest_param_service_and_source(proto.service_and_source, ros_msg.service_and_source) - ros_msg.service_and_source_is_set = proto.HasField("service_and_source") - convert_proto_to_bosdyn_msgs_area_i(proto.default_area, ros_msg.default_area) - ros_msg.default_area_is_set = proto.HasField("default_area") - ros_msg.allows_rectangle = proto.allows_rectangle - - -def convert_bosdyn_msgs_region_of_interest_param_spec_to_proto(ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParamSpec", proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam.Spec") -> None: - proto.Clear() - if ros_msg.service_and_source_is_set: - convert_bosdyn_msgs_region_of_interest_param_service_and_source_to_proto(ros_msg.service_and_source, proto.service_and_source) - if ros_msg.default_area_is_set: - convert_bosdyn_msgs_area_i_to_proto(ros_msg.default_area, proto.default_area) - proto.allows_rectangle = ros_msg.allows_rectangle - - -def convert_proto_to_bosdyn_msgs_region_of_interest_param(proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam", ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParam") -> None: - convert_proto_to_bosdyn_msgs_area_i(proto.area, ros_msg.area) - ros_msg.area_is_set = proto.HasField("area") - convert_proto_to_bosdyn_msgs_region_of_interest_param_service_and_source(proto.service_and_source, ros_msg.service_and_source) - ros_msg.service_and_source_is_set = proto.HasField("service_and_source") - ros_msg.image_cols = proto.image_cols - ros_msg.image_rows = proto.image_rows - - -def convert_bosdyn_msgs_region_of_interest_param_to_proto(ros_msg: "bosdyn_msgs.msgs.RegionOfInterestParam", proto: "bosdyn.api.service_customization_pb2.RegionOfInterestParam") -> None: - proto.Clear() - if ros_msg.area_is_set: - convert_bosdyn_msgs_area_i_to_proto(ros_msg.area, proto.area) - if ros_msg.service_and_source_is_set: - convert_bosdyn_msgs_region_of_interest_param_service_and_source_to_proto(ros_msg.service_and_source, proto.service_and_source) - proto.image_cols = ros_msg.image_cols - proto.image_rows = ros_msg.image_rows - - -def convert_proto_to_bosdyn_msgs_custom_param_error_status(proto: "bosdyn.api.service_customization_pb2.CustomParamError.Status", ros_msg: "bosdyn_msgs.msgs.CustomParamErrorStatus") -> None: - pass - - -def convert_bosdyn_msgs_custom_param_error_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamErrorStatus", proto: "bosdyn.api.service_customization_pb2.CustomParamError.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_custom_param_error(proto: "bosdyn.api.service_customization_pb2.CustomParamError", ros_msg: "bosdyn_msgs.msgs.CustomParamError") -> None: - ros_msg.status.value = proto.status - ros_msg.error_messages = [] - for _item in proto.error_messages: - ros_msg.error_messages.append(_item) - - -def convert_bosdyn_msgs_custom_param_error_to_proto(ros_msg: "bosdyn_msgs.msgs.CustomParamError", proto: "bosdyn.api.service_customization_pb2.CustomParamError") -> None: - proto.Clear() - proto.status = ros_msg.status.value - del proto.error_messages[:] - for _item in ros_msg.error_messages: - proto.error_messages.append(_item) - - -def convert_proto_to_bosdyn_msgs_service_fault_id(proto: "bosdyn.api.service_fault_pb2.ServiceFaultId", ros_msg: "bosdyn_msgs.msgs.ServiceFaultId") -> None: - ros_msg.fault_name = proto.fault_name - ros_msg.service_name = proto.service_name - ros_msg.payload_guid = proto.payload_guid - - -def convert_bosdyn_msgs_service_fault_id_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceFaultId", proto: "bosdyn.api.service_fault_pb2.ServiceFaultId") -> None: - proto.Clear() - proto.fault_name = ros_msg.fault_name - proto.service_name = ros_msg.service_name - proto.payload_guid = ros_msg.payload_guid - - -def convert_proto_to_bosdyn_msgs_service_fault_severity(proto: "bosdyn.api.service_fault_pb2.ServiceFault.Severity", ros_msg: "bosdyn_msgs.msgs.ServiceFaultSeverity") -> None: - pass - - -def convert_bosdyn_msgs_service_fault_severity_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceFaultSeverity", proto: "bosdyn.api.service_fault_pb2.ServiceFault.Severity") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_service_fault(proto: "bosdyn.api.service_fault_pb2.ServiceFault", ros_msg: "bosdyn_msgs.msgs.ServiceFault") -> None: - convert_proto_to_bosdyn_msgs_service_fault_id(proto.fault_id, ros_msg.fault_id) - ros_msg.fault_id_is_set = proto.HasField("fault_id") - ros_msg.error_message = proto.error_message - ros_msg.attributes = [] - for _item in proto.attributes: - ros_msg.attributes.append(_item) - ros_msg.severity.value = proto.severity - convert_proto_to_builtin_interfaces_time(proto.onset_timestamp, ros_msg.onset_timestamp) - ros_msg.onset_timestamp_is_set = proto.HasField("onset_timestamp") - convert_proto_to_builtin_interfaces_duration(proto.duration, ros_msg.duration) - ros_msg.duration_is_set = proto.HasField("duration") - - -def convert_bosdyn_msgs_service_fault_to_proto(ros_msg: "bosdyn_msgs.msgs.ServiceFault", proto: "bosdyn.api.service_fault_pb2.ServiceFault") -> None: - proto.Clear() - if ros_msg.fault_id_is_set: - convert_bosdyn_msgs_service_fault_id_to_proto(ros_msg.fault_id, proto.fault_id) - proto.error_message = ros_msg.error_message - del proto.attributes[:] - for _item in ros_msg.attributes: - proto.attributes.append(_item) - proto.severity = ros_msg.severity.value - if ros_msg.onset_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.onset_timestamp, proto.onset_timestamp) - if ros_msg.duration_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.duration, proto.duration) - - -def convert_proto_to_bosdyn_msgs_trigger_service_fault_request(proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultRequest", ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_service_fault(proto.fault, ros_msg.fault) - ros_msg.fault_is_set = proto.HasField("fault") - - -def convert_bosdyn_msgs_trigger_service_fault_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultRequest", proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.fault_is_set: - convert_bosdyn_msgs_service_fault_to_proto(ros_msg.fault, proto.fault) - - -def convert_proto_to_bosdyn_msgs_trigger_service_fault_response_status(proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultResponse.Status", ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_trigger_service_fault_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultResponseStatus", proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_trigger_service_fault_response(proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultResponse", ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_trigger_service_fault_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TriggerServiceFaultResponse", proto: "bosdyn.api.service_fault_pb2.TriggerServiceFaultResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_clear_service_fault_request(proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultRequest", ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_service_fault_id(proto.fault_id, ros_msg.fault_id) - ros_msg.fault_id_is_set = proto.HasField("fault_id") - ros_msg.clear_all_service_faults = proto.clear_all_service_faults - ros_msg.clear_all_payload_faults = proto.clear_all_payload_faults - - -def convert_bosdyn_msgs_clear_service_fault_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultRequest", proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.fault_id_is_set: - convert_bosdyn_msgs_service_fault_id_to_proto(ros_msg.fault_id, proto.fault_id) - proto.clear_all_service_faults = ros_msg.clear_all_service_faults - proto.clear_all_payload_faults = ros_msg.clear_all_payload_faults - - -def convert_proto_to_bosdyn_msgs_clear_service_fault_response_status(proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultResponse.Status", ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_clear_service_fault_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultResponseStatus", proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_clear_service_fault_response(proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultResponse", ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - - -def convert_bosdyn_msgs_clear_service_fault_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearServiceFaultResponse", proto: "bosdyn.api.service_fault_pb2.ClearServiceFaultResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - - -def convert_proto_to_bosdyn_msgs_keypoint(proto: "bosdyn.api.sparse_features_pb2.Keypoint", ros_msg: "bosdyn_msgs.msgs.Keypoint") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.coordinates, ros_msg.coordinates) - ros_msg.coordinates_is_set = proto.HasField("coordinates") - ros_msg.binary_descriptor = proto.binary_descriptor - ros_msg.score = proto.score - ros_msg.size = proto.size - ros_msg.angle = proto.angle - - -def convert_bosdyn_msgs_keypoint_to_proto(ros_msg: "bosdyn_msgs.msgs.Keypoint", proto: "bosdyn.api.sparse_features_pb2.Keypoint") -> None: - proto.Clear() - if ros_msg.coordinates_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.coordinates, proto.coordinates) - proto.binary_descriptor = ros_msg.binary_descriptor - proto.score = ros_msg.score - proto.size = ros_msg.size - proto.angle = ros_msg.angle - - -def convert_proto_to_bosdyn_msgs_keypoint_set_keypoint_type(proto: "bosdyn.api.sparse_features_pb2.KeypointSet.KeypointType", ros_msg: "bosdyn_msgs.msgs.KeypointSetKeypointType") -> None: - pass - - -def convert_bosdyn_msgs_keypoint_set_keypoint_type_to_proto(ros_msg: "bosdyn_msgs.msgs.KeypointSetKeypointType", proto: "bosdyn.api.sparse_features_pb2.KeypointSet.KeypointType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_keypoint_set(proto: "bosdyn.api.sparse_features_pb2.KeypointSet", ros_msg: "bosdyn_msgs.msgs.KeypointSet") -> None: - from bosdyn_msgs.msg import Keypoint - ros_msg.keypoints = [] - for _item in proto.keypoints: - ros_msg.keypoints.append(Keypoint()) - convert_proto_to_bosdyn_msgs_keypoint(_item, ros_msg.keypoints[-1]) - ros_msg.type.value = proto.type - - -def convert_bosdyn_msgs_keypoint_set_to_proto(ros_msg: "bosdyn_msgs.msgs.KeypointSet", proto: "bosdyn.api.sparse_features_pb2.KeypointSet") -> None: - proto.Clear() - del proto.keypoints[:] - for _item in ros_msg.keypoints: - convert_bosdyn_msgs_keypoint_to_proto(_item, proto.keypoints.add()) - proto.type = ros_msg.type.value - - -def convert_proto_to_bosdyn_msgs_match(proto: "bosdyn.api.sparse_features_pb2.Match", ros_msg: "bosdyn_msgs.msgs.Match") -> None: - ros_msg.reference_index = proto.reference_index - ros_msg.live_index = proto.live_index - ros_msg.distance = proto.distance - - -def convert_bosdyn_msgs_match_to_proto(ros_msg: "bosdyn_msgs.msgs.Match", proto: "bosdyn.api.sparse_features_pb2.Match") -> None: - proto.Clear() - proto.reference_index = ros_msg.reference_index - proto.live_index = ros_msg.live_index - proto.distance = ros_msg.distance - - -def convert_proto_to_bosdyn_msgs_keypoint_matches(proto: "bosdyn.api.sparse_features_pb2.KeypointMatches", ros_msg: "bosdyn_msgs.msgs.KeypointMatches") -> None: - convert_proto_to_bosdyn_msgs_keypoint_set(proto.reference_keypoints, ros_msg.reference_keypoints) - ros_msg.reference_keypoints_is_set = proto.HasField("reference_keypoints") - convert_proto_to_bosdyn_msgs_keypoint_set(proto.live_keypoints, ros_msg.live_keypoints) - ros_msg.live_keypoints_is_set = proto.HasField("live_keypoints") - from bosdyn_msgs.msg import Match - ros_msg.matches = [] - for _item in proto.matches: - ros_msg.matches.append(Match()) - convert_proto_to_bosdyn_msgs_match(_item, ros_msg.matches[-1]) - - -def convert_bosdyn_msgs_keypoint_matches_to_proto(ros_msg: "bosdyn_msgs.msgs.KeypointMatches", proto: "bosdyn.api.sparse_features_pb2.KeypointMatches") -> None: - proto.Clear() - if ros_msg.reference_keypoints_is_set: - convert_bosdyn_msgs_keypoint_set_to_proto(ros_msg.reference_keypoints, proto.reference_keypoints) - if ros_msg.live_keypoints_is_set: - convert_bosdyn_msgs_keypoint_set_to_proto(ros_msg.live_keypoints, proto.live_keypoints) - del proto.matches[:] - for _item in ros_msg.matches: - convert_bosdyn_msgs_match_to_proto(_item, proto.matches.add()) - - -def convert_proto_to_bosdyn_msgs_open_door_command_request(proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandRequest", ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - convert_proto_to_bosdyn_msgs_door_command_request(proto.door_command, ros_msg.door_command) - ros_msg.door_command_is_set = proto.HasField("door_command") - - -def convert_bosdyn_msgs_open_door_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandRequest", proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - if ros_msg.door_command_is_set: - convert_bosdyn_msgs_door_command_request_to_proto(ros_msg.door_command, proto.door_command) - - -def convert_proto_to_bosdyn_msgs_open_door_command_response_status(proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandResponse.Status", ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_open_door_command_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandResponseStatus", proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_open_door_command_response(proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandResponse", ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.message = proto.message - ros_msg.door_command_id = proto.door_command_id - - -def convert_bosdyn_msgs_open_door_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.OpenDoorCommandResponse", proto: "bosdyn.api.spot.door_pb2.OpenDoorCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.message = ros_msg.message - proto.door_command_id = ros_msg.door_command_id - - -def convert_proto_to_bosdyn_msgs_open_door_feedback_request(proto: "bosdyn.api.spot.door_pb2.OpenDoorFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.OpenDoorFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.door_command_id = proto.door_command_id - - -def convert_bosdyn_msgs_open_door_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.OpenDoorFeedbackRequest", proto: "bosdyn.api.spot.door_pb2.OpenDoorFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.door_command_id = ros_msg.door_command_id - - -def convert_proto_to_bosdyn_msgs_open_door_feedback_response(proto: "bosdyn.api.spot.door_pb2.OpenDoorFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.OpenDoorFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - convert_proto_to_bosdyn_msgs_door_command_feedback(proto.feedback, ros_msg.feedback) - ros_msg.feedback_is_set = proto.HasField("feedback") - - -def convert_bosdyn_msgs_open_door_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.OpenDoorFeedbackResponse", proto: "bosdyn.api.spot.door_pb2.OpenDoorFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - if ros_msg.feedback_is_set: - convert_bosdyn_msgs_door_command_feedback_to_proto(ros_msg.feedback, proto.feedback) - - -def convert_proto_to_bosdyn_msgs_door_command_hinge_side(proto: "bosdyn.api.spot.door_pb2.DoorCommand.HingeSide", ros_msg: "bosdyn_msgs.msgs.DoorCommandHingeSide") -> None: - pass - - -def convert_bosdyn_msgs_door_command_hinge_side_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandHingeSide", proto: "bosdyn.api.spot.door_pb2.DoorCommand.HingeSide") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_door_command_swing_direction(proto: "bosdyn.api.spot.door_pb2.DoorCommand.SwingDirection", ros_msg: "bosdyn_msgs.msgs.DoorCommandSwingDirection") -> None: - pass - - -def convert_bosdyn_msgs_door_command_swing_direction_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandSwingDirection", proto: "bosdyn.api.spot.door_pb2.DoorCommand.SwingDirection") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_door_command_handle_type(proto: "bosdyn.api.spot.door_pb2.DoorCommand.HandleType", ros_msg: "bosdyn_msgs.msgs.DoorCommandHandleType") -> None: - pass - - -def convert_bosdyn_msgs_door_command_handle_type_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandHandleType", proto: "bosdyn.api.spot.door_pb2.DoorCommand.HandleType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_door_command_auto_grasp_command(proto: "bosdyn.api.spot.door_pb2.DoorCommand.AutoGraspCommand", ros_msg: "bosdyn_msgs.msgs.DoorCommandAutoGraspCommand") -> None: - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.search_ray_start_in_frame, ros_msg.search_ray_start_in_frame) - ros_msg.search_ray_start_in_frame_is_set = proto.HasField("search_ray_start_in_frame") - convert_proto_to_geometry_msgs_vector3(proto.search_ray_end_in_frame, ros_msg.search_ray_end_in_frame) - ros_msg.search_ray_end_in_frame_is_set = proto.HasField("search_ray_end_in_frame") - ros_msg.hinge_side.value = proto.hinge_side - ros_msg.swing_direction.value = proto.swing_direction - - -def convert_bosdyn_msgs_door_command_auto_grasp_command_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandAutoGraspCommand", proto: "bosdyn.api.spot.door_pb2.DoorCommand.AutoGraspCommand") -> None: - proto.Clear() - proto.frame_name = ros_msg.frame_name - if ros_msg.search_ray_start_in_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.search_ray_start_in_frame, proto.search_ray_start_in_frame) - if ros_msg.search_ray_end_in_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.search_ray_end_in_frame, proto.search_ray_end_in_frame) - proto.hinge_side = ros_msg.hinge_side.value - proto.swing_direction = ros_msg.swing_direction.value - - -def convert_proto_to_bosdyn_msgs_door_command_warmstart_command(proto: "bosdyn.api.spot.door_pb2.DoorCommand.WarmstartCommand", ros_msg: "bosdyn_msgs.msgs.DoorCommandWarmstartCommand") -> None: - ros_msg.hinge_side.value = proto.hinge_side - ros_msg.swing_direction.value = proto.swing_direction - ros_msg.handle_type.value = proto.handle_type - - -def convert_bosdyn_msgs_door_command_warmstart_command_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandWarmstartCommand", proto: "bosdyn.api.spot.door_pb2.DoorCommand.WarmstartCommand") -> None: - proto.Clear() - proto.hinge_side = ros_msg.hinge_side.value - proto.swing_direction = ros_msg.swing_direction.value - proto.handle_type = ros_msg.handle_type.value - - -def convert_proto_to_bosdyn_msgs_door_command_auto_push_command(proto: "bosdyn.api.spot.door_pb2.DoorCommand.AutoPushCommand", ros_msg: "bosdyn_msgs.msgs.DoorCommandAutoPushCommand") -> None: - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.push_point_in_frame, ros_msg.push_point_in_frame) - ros_msg.push_point_in_frame_is_set = proto.HasField("push_point_in_frame") - ros_msg.hinge_side.value = proto.hinge_side - - -def convert_bosdyn_msgs_door_command_auto_push_command_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandAutoPushCommand", proto: "bosdyn.api.spot.door_pb2.DoorCommand.AutoPushCommand") -> None: - proto.Clear() - proto.frame_name = ros_msg.frame_name - if ros_msg.push_point_in_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.push_point_in_frame, proto.push_point_in_frame) - proto.hinge_side = ros_msg.hinge_side.value - - -def convert_proto_to_bosdyn_msgs_door_command_request_one_of_command(proto: "bosdyn.api.spot.door_pb2.DoorCommand.Request", ros_msg: "bosdyn_msgs.msgs.DoorCommandRequestOneOfCommand") -> None: - if proto.HasField("auto_grasp_command"): - ros_msg.command_choice = ros_msg.COMMAND_AUTO_GRASP_COMMAND_SET - convert_proto_to_bosdyn_msgs_door_command_auto_grasp_command(proto.auto_grasp_command, ros_msg.auto_grasp_command) - if proto.HasField("warmstart_command"): - ros_msg.command_choice = ros_msg.COMMAND_WARMSTART_COMMAND_SET - convert_proto_to_bosdyn_msgs_door_command_warmstart_command(proto.warmstart_command, ros_msg.warmstart_command) - if proto.HasField("auto_push_command"): - ros_msg.command_choice = ros_msg.COMMAND_AUTO_PUSH_COMMAND_SET - convert_proto_to_bosdyn_msgs_door_command_auto_push_command(proto.auto_push_command, ros_msg.auto_push_command) - - -def convert_bosdyn_msgs_door_command_request_one_of_command_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandRequestOneOfCommand", proto: "bosdyn.api.spot.door_pb2.DoorCommand.Request") -> None: - proto.ClearField("command") - if ros_msg.command_choice == ros_msg.COMMAND_AUTO_GRASP_COMMAND_SET: - convert_bosdyn_msgs_door_command_auto_grasp_command_to_proto(ros_msg.auto_grasp_command, proto.auto_grasp_command) - if ros_msg.command_choice == ros_msg.COMMAND_WARMSTART_COMMAND_SET: - convert_bosdyn_msgs_door_command_warmstart_command_to_proto(ros_msg.warmstart_command, proto.warmstart_command) - if ros_msg.command_choice == ros_msg.COMMAND_AUTO_PUSH_COMMAND_SET: - convert_bosdyn_msgs_door_command_auto_push_command_to_proto(ros_msg.auto_push_command, proto.auto_push_command) - - -def convert_proto_to_bosdyn_msgs_door_command_request(proto: "bosdyn.api.spot.door_pb2.DoorCommand.Request", ros_msg: "bosdyn_msgs.msgs.DoorCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_door_command_request_one_of_command(proto, ros_msg.command) - - -def convert_bosdyn_msgs_door_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandRequest", proto: "bosdyn.api.spot.door_pb2.DoorCommand.Request") -> None: - proto.Clear() - convert_bosdyn_msgs_door_command_request_one_of_command_to_proto(ros_msg.command, proto) - - -def convert_proto_to_bosdyn_msgs_door_command_feedback_status(proto: "bosdyn.api.spot.door_pb2.DoorCommand.Feedback.Status", ros_msg: "bosdyn_msgs.msgs.DoorCommandFeedbackStatus") -> None: - pass - - -def convert_bosdyn_msgs_door_command_feedback_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandFeedbackStatus", proto: "bosdyn.api.spot.door_pb2.DoorCommand.Feedback.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_door_command_feedback(proto: "bosdyn.api.spot.door_pb2.DoorCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.DoorCommandFeedback") -> None: - ros_msg.status.value = proto.status - ros_msg.distance_past_threshold = proto.distance_past_threshold - - -def convert_bosdyn_msgs_door_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommandFeedback", proto: "bosdyn.api.spot.door_pb2.DoorCommand.Feedback") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.distance_past_threshold = ros_msg.distance_past_threshold - - -def convert_proto_to_bosdyn_msgs_door_command(proto: "bosdyn.api.spot.door_pb2.DoorCommand", ros_msg: "bosdyn_msgs.msgs.DoorCommand") -> None: - pass - - -def convert_bosdyn_msgs_door_command_to_proto(ros_msg: "bosdyn_msgs.msgs.DoorCommand", proto: "bosdyn.api.spot.door_pb2.DoorCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_area_callback_door_config(proto: "bosdyn.api.spot.door_area_callback_pb2.AreaCallbackDoorConfig", ros_msg: "bosdyn_msgs.msgs.AreaCallbackDoorConfig") -> None: - convert_proto_to_bosdyn_msgs_door_command_request(proto.forward_command, ros_msg.forward_command) - ros_msg.forward_command_is_set = proto.HasField("forward_command") - convert_proto_to_bosdyn_msgs_door_command_request(proto.reverse_command, ros_msg.reverse_command) - ros_msg.reverse_command_is_set = proto.HasField("reverse_command") - - -def convert_bosdyn_msgs_area_callback_door_config_to_proto(ros_msg: "bosdyn_msgs.msgs.AreaCallbackDoorConfig", proto: "bosdyn.api.spot.door_area_callback_pb2.AreaCallbackDoorConfig") -> None: - proto.Clear() - if ros_msg.forward_command_is_set: - convert_bosdyn_msgs_door_command_request_to_proto(ros_msg.forward_command, proto.forward_command) - if ros_msg.reverse_command_is_set: - convert_bosdyn_msgs_door_command_request_to_proto(ros_msg.reverse_command, proto.reverse_command) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_named_arm_configuration(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.NamedArmConfiguration", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestNamedArmConfiguration") -> None: - pass - - -def convert_bosdyn_msgs_inverse_kinematics_request_named_arm_configuration_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestNamedArmConfiguration", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.NamedArmConfiguration") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_fixed_stance(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.FixedStance", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestFixedStance") -> None: - convert_proto_to_geometry_msgs_vector3(proto.fl_rt_scene, ros_msg.fl_rt_scene) - ros_msg.fl_rt_scene_is_set = proto.HasField("fl_rt_scene") - convert_proto_to_geometry_msgs_vector3(proto.fr_rt_scene, ros_msg.fr_rt_scene) - ros_msg.fr_rt_scene_is_set = proto.HasField("fr_rt_scene") - convert_proto_to_geometry_msgs_vector3(proto.hl_rt_scene, ros_msg.hl_rt_scene) - ros_msg.hl_rt_scene_is_set = proto.HasField("hl_rt_scene") - convert_proto_to_geometry_msgs_vector3(proto.hr_rt_scene, ros_msg.hr_rt_scene) - ros_msg.hr_rt_scene_is_set = proto.HasField("hr_rt_scene") - - -def convert_bosdyn_msgs_inverse_kinematics_request_fixed_stance_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestFixedStance", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.FixedStance") -> None: - proto.Clear() - if ros_msg.fl_rt_scene_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.fl_rt_scene, proto.fl_rt_scene) - if ros_msg.fr_rt_scene_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.fr_rt_scene, proto.fr_rt_scene) - if ros_msg.hl_rt_scene_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.hl_rt_scene, proto.hl_rt_scene) - if ros_msg.hr_rt_scene_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.hr_rt_scene, proto.hr_rt_scene) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_on_ground_plane_stance(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.OnGroundPlaneStance", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOnGroundPlaneStance") -> None: - convert_proto_to_geometry_msgs_pose(proto.scene_tform_ground, ros_msg.scene_tform_ground) - ros_msg.scene_tform_ground_is_set = proto.HasField("scene_tform_ground") - - -def convert_bosdyn_msgs_inverse_kinematics_request_on_ground_plane_stance_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOnGroundPlaneStance", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.OnGroundPlaneStance") -> None: - proto.Clear() - if ros_msg.scene_tform_ground_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.scene_tform_ground, proto.scene_tform_ground) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_stance_specification(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfStanceSpecification") -> None: - if proto.HasField("fixed_stance"): - ros_msg.stance_specification_choice = ros_msg.STANCE_SPECIFICATION_FIXED_STANCE_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_fixed_stance(proto.fixed_stance, ros_msg.fixed_stance) - if proto.HasField("on_ground_plane_stance"): - ros_msg.stance_specification_choice = ros_msg.STANCE_SPECIFICATION_ON_GROUND_PLANE_STANCE_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_on_ground_plane_stance(proto.on_ground_plane_stance, ros_msg.on_ground_plane_stance) - - -def convert_bosdyn_msgs_inverse_kinematics_request_one_of_stance_specification_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfStanceSpecification", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest") -> None: - proto.ClearField("stance_specification") - if ros_msg.stance_specification_choice == ros_msg.STANCE_SPECIFICATION_FIXED_STANCE_SET: - convert_bosdyn_msgs_inverse_kinematics_request_fixed_stance_to_proto(ros_msg.fixed_stance, proto.fixed_stance) - if ros_msg.stance_specification_choice == ros_msg.STANCE_SPECIFICATION_ON_GROUND_PLANE_STANCE_SET: - convert_bosdyn_msgs_inverse_kinematics_request_on_ground_plane_stance_to_proto(ros_msg.on_ground_plane_stance, proto.on_ground_plane_stance) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_wrist_mounted_tool(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.WristMountedTool", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestWristMountedTool") -> None: - convert_proto_to_geometry_msgs_pose(proto.wrist_tform_tool, ros_msg.wrist_tform_tool) - ros_msg.wrist_tform_tool_is_set = proto.HasField("wrist_tform_tool") - - -def convert_bosdyn_msgs_inverse_kinematics_request_wrist_mounted_tool_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestWristMountedTool", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.WristMountedTool") -> None: - proto.Clear() - if ros_msg.wrist_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.wrist_tform_tool, proto.wrist_tform_tool) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_body_mounted_tool(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.BodyMountedTool", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestBodyMountedTool") -> None: - convert_proto_to_geometry_msgs_pose(proto.body_tform_tool, ros_msg.body_tform_tool) - ros_msg.body_tform_tool_is_set = proto.HasField("body_tform_tool") - - -def convert_bosdyn_msgs_inverse_kinematics_request_body_mounted_tool_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestBodyMountedTool", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.BodyMountedTool") -> None: - proto.Clear() - if ros_msg.body_tform_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.body_tform_tool, proto.body_tform_tool) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_tool_specification(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfToolSpecification") -> None: - if proto.HasField("wrist_mounted_tool"): - ros_msg.tool_specification_choice = ros_msg.TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_wrist_mounted_tool(proto.wrist_mounted_tool, ros_msg.wrist_mounted_tool) - if proto.HasField("body_mounted_tool"): - ros_msg.tool_specification_choice = ros_msg.TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_body_mounted_tool(proto.body_mounted_tool, ros_msg.body_mounted_tool) - - -def convert_bosdyn_msgs_inverse_kinematics_request_one_of_tool_specification_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfToolSpecification", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest") -> None: - proto.ClearField("tool_specification") - if ros_msg.tool_specification_choice == ros_msg.TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET: - convert_bosdyn_msgs_inverse_kinematics_request_wrist_mounted_tool_to_proto(ros_msg.wrist_mounted_tool, proto.wrist_mounted_tool) - if ros_msg.tool_specification_choice == ros_msg.TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET: - convert_bosdyn_msgs_inverse_kinematics_request_body_mounted_tool_to_proto(ros_msg.body_mounted_tool, proto.body_mounted_tool) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_tool_pose_task(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.ToolPoseTask", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestToolPoseTask") -> None: - convert_proto_to_geometry_msgs_pose(proto.task_tform_desired_tool, ros_msg.task_tform_desired_tool) - ros_msg.task_tform_desired_tool_is_set = proto.HasField("task_tform_desired_tool") - - -def convert_bosdyn_msgs_inverse_kinematics_request_tool_pose_task_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestToolPoseTask", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.ToolPoseTask") -> None: - proto.Clear() - if ros_msg.task_tform_desired_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.task_tform_desired_tool, proto.task_tform_desired_tool) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_tool_gaze_task(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.ToolGazeTask", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestToolGazeTask") -> None: - convert_proto_to_geometry_msgs_vector3(proto.target_in_task, ros_msg.target_in_task) - ros_msg.target_in_task_is_set = proto.HasField("target_in_task") - convert_proto_to_geometry_msgs_pose(proto.task_tform_desired_tool, ros_msg.task_tform_desired_tool) - ros_msg.task_tform_desired_tool_is_set = proto.HasField("task_tform_desired_tool") - - -def convert_bosdyn_msgs_inverse_kinematics_request_tool_gaze_task_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestToolGazeTask", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest.ToolGazeTask") -> None: - proto.Clear() - if ros_msg.target_in_task_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.target_in_task, proto.target_in_task) - if ros_msg.task_tform_desired_tool_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.task_tform_desired_tool, proto.task_tform_desired_tool) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_task_specification(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfTaskSpecification") -> None: - if proto.HasField("tool_pose_task"): - ros_msg.task_specification_choice = ros_msg.TASK_SPECIFICATION_TOOL_POSE_TASK_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_tool_pose_task(proto.tool_pose_task, ros_msg.tool_pose_task) - if proto.HasField("tool_gaze_task"): - ros_msg.task_specification_choice = ros_msg.TASK_SPECIFICATION_TOOL_GAZE_TASK_SET - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_tool_gaze_task(proto.tool_gaze_task, ros_msg.tool_gaze_task) - - -def convert_bosdyn_msgs_inverse_kinematics_request_one_of_task_specification_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequestOneOfTaskSpecification", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest") -> None: - proto.ClearField("task_specification") - if ros_msg.task_specification_choice == ros_msg.TASK_SPECIFICATION_TOOL_POSE_TASK_SET: - convert_bosdyn_msgs_inverse_kinematics_request_tool_pose_task_to_proto(ros_msg.tool_pose_task, proto.tool_pose_task) - if ros_msg.task_specification_choice == ros_msg.TASK_SPECIFICATION_TOOL_GAZE_TASK_SET: - convert_bosdyn_msgs_inverse_kinematics_request_tool_gaze_task_to_proto(ros_msg.tool_gaze_task, proto.tool_gaze_task) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_request(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.root_frame_name = proto.root_frame_name - convert_proto_to_geometry_msgs_pose(proto.root_tform_scene, ros_msg.root_tform_scene) - ros_msg.root_tform_scene_is_set = proto.HasField("root_tform_scene") - convert_proto_to_geometry_msgs_pose(proto.scene_tform_task, ros_msg.scene_tform_task) - ros_msg.scene_tform_task_is_set = proto.HasField("scene_tform_task") - ros_msg.nominal_arm_configuration.value = proto.nominal_arm_configuration - convert_proto_to_bosdyn_msgs_arm_joint_position(proto.nominal_arm_configuration_overrides, ros_msg.nominal_arm_configuration_overrides) - ros_msg.nominal_arm_configuration_overrides_is_set = proto.HasField("nominal_arm_configuration_overrides") - convert_proto_to_geometry_msgs_pose(proto.scene_tform_body_nominal, ros_msg.scene_tform_body_nominal) - ros_msg.scene_tform_body_nominal_is_set = proto.HasField("scene_tform_body_nominal") - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_stance_specification(proto, ros_msg.stance_specification) - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_tool_specification(proto, ros_msg.tool_specification) - convert_proto_to_bosdyn_msgs_inverse_kinematics_request_one_of_task_specification(proto, ros_msg.task_specification) - - -def convert_bosdyn_msgs_inverse_kinematics_request_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsRequest", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.root_frame_name = ros_msg.root_frame_name - if ros_msg.root_tform_scene_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.root_tform_scene, proto.root_tform_scene) - if ros_msg.scene_tform_task_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.scene_tform_task, proto.scene_tform_task) - proto.nominal_arm_configuration = ros_msg.nominal_arm_configuration.value - if ros_msg.nominal_arm_configuration_overrides_is_set: - convert_bosdyn_msgs_arm_joint_position_to_proto(ros_msg.nominal_arm_configuration_overrides, proto.nominal_arm_configuration_overrides) - if ros_msg.scene_tform_body_nominal_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.scene_tform_body_nominal, proto.scene_tform_body_nominal) - convert_bosdyn_msgs_inverse_kinematics_request_one_of_stance_specification_to_proto(ros_msg.stance_specification, proto) - convert_bosdyn_msgs_inverse_kinematics_request_one_of_tool_specification_to_proto(ros_msg.tool_specification, proto) - convert_bosdyn_msgs_inverse_kinematics_request_one_of_task_specification_to_proto(ros_msg.task_specification, proto) - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_response_status(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsResponse.Status", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_inverse_kinematics_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsResponseStatus", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_inverse_kinematics_response(proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsResponse", ros_msg: "bosdyn_msgs.msgs.InverseKinematicsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - convert_proto_to_bosdyn_msgs_kinematic_state(proto.robot_configuration, ros_msg.robot_configuration) - ros_msg.robot_configuration_is_set = proto.HasField("robot_configuration") - - -def convert_bosdyn_msgs_inverse_kinematics_response_to_proto(ros_msg: "bosdyn_msgs.msgs.InverseKinematicsResponse", proto: "bosdyn.api.spot.inverse_kinematics_pb2.InverseKinematicsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - if ros_msg.robot_configuration_is_set: - convert_bosdyn_msgs_kinematic_state_to_proto(ros_msg.robot_configuration, proto.robot_configuration) - - -def convert_proto_to_bosdyn_msgs_locomotion_hint(proto: "bosdyn.api.spot.robot_command_pb2.LocomotionHint", ros_msg: "bosdyn_msgs.msgs.LocomotionHint") -> None: - pass - - -def convert_bosdyn_msgs_locomotion_hint_to_proto(ros_msg: "bosdyn_msgs.msgs.LocomotionHint", proto: "bosdyn.api.spot.robot_command_pb2.LocomotionHint") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_swing_height(proto: "bosdyn.api.spot.robot_command_pb2.SwingHeight", ros_msg: "bosdyn_msgs.msgs.SwingHeight") -> None: - pass - - -def convert_bosdyn_msgs_swing_height_to_proto(ros_msg: "bosdyn_msgs.msgs.SwingHeight", proto: "bosdyn.api.spot.robot_command_pb2.SwingHeight") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_mobility_params_stairs_mode(proto: "bosdyn.api.spot.robot_command_pb2.MobilityParams.StairsMode", ros_msg: "bosdyn_msgs.msgs.MobilityParamsStairsMode") -> None: - pass - - -def convert_bosdyn_msgs_mobility_params_stairs_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityParamsStairsMode", proto: "bosdyn.api.spot.robot_command_pb2.MobilityParams.StairsMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_mobility_params(proto: "bosdyn.api.spot.robot_command_pb2.MobilityParams", ros_msg: "bosdyn_msgs.msgs.MobilityParams") -> None: - convert_proto_to_bosdyn_msgs_se2_velocity_limit(proto.vel_limit, ros_msg.vel_limit) - ros_msg.vel_limit_is_set = proto.HasField("vel_limit") - convert_proto_to_bosdyn_msgs_body_control_params(proto.body_control, ros_msg.body_control) - ros_msg.body_control_is_set = proto.HasField("body_control") - ros_msg.locomotion_hint.value = proto.locomotion_hint - ros_msg.stairs_mode.value = proto.stairs_mode - ros_msg.allow_degraded_perception = proto.allow_degraded_perception - convert_proto_to_bosdyn_msgs_obstacle_params(proto.obstacle_params, ros_msg.obstacle_params) - ros_msg.obstacle_params_is_set = proto.HasField("obstacle_params") - ros_msg.swing_height.value = proto.swing_height - convert_proto_to_bosdyn_msgs_terrain_params(proto.terrain_params, ros_msg.terrain_params) - ros_msg.terrain_params_is_set = proto.HasField("terrain_params") - ros_msg.disallow_stair_tracker = proto.disallow_stair_tracker - ros_msg.disable_stair_error_auto_descent = proto.disable_stair_error_auto_descent - convert_proto_to_bosdyn_msgs_body_external_force_params(proto.external_force_params, ros_msg.external_force_params) - ros_msg.external_force_params_is_set = proto.HasField("external_force_params") - ros_msg.disallow_non_stairs_pitch_limiting = proto.disallow_non_stairs_pitch_limiting - ros_msg.disable_nearmap_cliff_avoidance = proto.disable_nearmap_cliff_avoidance - - -def convert_bosdyn_msgs_mobility_params_to_proto(ros_msg: "bosdyn_msgs.msgs.MobilityParams", proto: "bosdyn.api.spot.robot_command_pb2.MobilityParams") -> None: - proto.Clear() - if ros_msg.vel_limit_is_set: - convert_bosdyn_msgs_se2_velocity_limit_to_proto(ros_msg.vel_limit, proto.vel_limit) - if ros_msg.body_control_is_set: - convert_bosdyn_msgs_body_control_params_to_proto(ros_msg.body_control, proto.body_control) - proto.locomotion_hint = ros_msg.locomotion_hint.value - proto.stairs_mode = ros_msg.stairs_mode.value - proto.allow_degraded_perception = ros_msg.allow_degraded_perception - if ros_msg.obstacle_params_is_set: - convert_bosdyn_msgs_obstacle_params_to_proto(ros_msg.obstacle_params, proto.obstacle_params) - proto.swing_height = ros_msg.swing_height.value - if ros_msg.terrain_params_is_set: - convert_bosdyn_msgs_terrain_params_to_proto(ros_msg.terrain_params, proto.terrain_params) - proto.disallow_stair_tracker = ros_msg.disallow_stair_tracker - proto.disable_stair_error_auto_descent = ros_msg.disable_stair_error_auto_descent - if ros_msg.external_force_params_is_set: - convert_bosdyn_msgs_body_external_force_params_to_proto(ros_msg.external_force_params, proto.external_force_params) - proto.disallow_non_stairs_pitch_limiting = ros_msg.disallow_non_stairs_pitch_limiting - proto.disable_nearmap_cliff_avoidance = ros_msg.disable_nearmap_cliff_avoidance - - -def convert_proto_to_bosdyn_msgs_body_control_params_one_of_param(proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams", ros_msg: "bosdyn_msgs.msgs.BodyControlParamsOneOfParam") -> None: - if proto.HasField("base_offset_rt_footprint"): - ros_msg.param_choice = ros_msg.PARAM_BASE_OFFSET_RT_FOOTPRINT_SET - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.base_offset_rt_footprint, ros_msg.base_offset_rt_footprint) - if proto.HasField("body_assist_for_manipulation"): - ros_msg.param_choice = ros_msg.PARAM_BODY_ASSIST_FOR_MANIPULATION_SET - convert_proto_to_bosdyn_msgs_body_control_params_body_assist_for_manipulation(proto.body_assist_for_manipulation, ros_msg.body_assist_for_manipulation) - if proto.HasField("body_pose"): - ros_msg.param_choice = ros_msg.PARAM_BODY_POSE_SET - convert_proto_to_bosdyn_msgs_body_control_params_body_pose(proto.body_pose, ros_msg.body_pose) - - -def convert_bosdyn_msgs_body_control_params_one_of_param_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyControlParamsOneOfParam", proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams") -> None: - proto.ClearField("param") - if ros_msg.param_choice == ros_msg.PARAM_BASE_OFFSET_RT_FOOTPRINT_SET: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.base_offset_rt_footprint, proto.base_offset_rt_footprint) - if ros_msg.param_choice == ros_msg.PARAM_BODY_ASSIST_FOR_MANIPULATION_SET: - convert_bosdyn_msgs_body_control_params_body_assist_for_manipulation_to_proto(ros_msg.body_assist_for_manipulation, proto.body_assist_for_manipulation) - if ros_msg.param_choice == ros_msg.PARAM_BODY_POSE_SET: - convert_bosdyn_msgs_body_control_params_body_pose_to_proto(ros_msg.body_pose, proto.body_pose) - - -def convert_proto_to_bosdyn_msgs_body_control_params_rotation_setting(proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.RotationSetting", ros_msg: "bosdyn_msgs.msgs.BodyControlParamsRotationSetting") -> None: - pass - - -def convert_bosdyn_msgs_body_control_params_rotation_setting_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyControlParamsRotationSetting", proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.RotationSetting") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_body_control_params_body_assist_for_manipulation(proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.BodyAssistForManipulation", ros_msg: "bosdyn_msgs.msgs.BodyControlParamsBodyAssistForManipulation") -> None: - ros_msg.enable_body_yaw_assist = proto.enable_body_yaw_assist - ros_msg.enable_hip_height_assist = proto.enable_hip_height_assist - - -def convert_bosdyn_msgs_body_control_params_body_assist_for_manipulation_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyControlParamsBodyAssistForManipulation", proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.BodyAssistForManipulation") -> None: - proto.Clear() - proto.enable_body_yaw_assist = ros_msg.enable_body_yaw_assist - proto.enable_hip_height_assist = ros_msg.enable_hip_height_assist - - -def convert_proto_to_bosdyn_msgs_body_control_params_body_pose(proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.BodyPose", ros_msg: "bosdyn_msgs.msgs.BodyControlParamsBodyPose") -> None: - ros_msg.root_frame_name = proto.root_frame_name - convert_proto_to_bosdyn_msgs_se3_trajectory(proto.base_offset_rt_root, ros_msg.base_offset_rt_root) - ros_msg.base_offset_rt_root_is_set = proto.HasField("base_offset_rt_root") - - -def convert_bosdyn_msgs_body_control_params_body_pose_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyControlParamsBodyPose", proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams.BodyPose") -> None: - proto.Clear() - proto.root_frame_name = ros_msg.root_frame_name - if ros_msg.base_offset_rt_root_is_set: - convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg.base_offset_rt_root, proto.base_offset_rt_root) - - -def convert_proto_to_bosdyn_msgs_body_control_params(proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams", ros_msg: "bosdyn_msgs.msgs.BodyControlParams") -> None: - convert_proto_to_bosdyn_msgs_body_control_params_one_of_param(proto, ros_msg.param) - ros_msg.rotation_setting.value = proto.rotation_setting - - -def convert_bosdyn_msgs_body_control_params_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyControlParams", proto: "bosdyn.api.spot.robot_command_pb2.BodyControlParams") -> None: - proto.Clear() - convert_bosdyn_msgs_body_control_params_one_of_param_to_proto(ros_msg.param, proto) - proto.rotation_setting = ros_msg.rotation_setting.value - - -def convert_proto_to_bosdyn_msgs_obstacle_params(proto: "bosdyn.api.spot.robot_command_pb2.ObstacleParams", ros_msg: "bosdyn_msgs.msgs.ObstacleParams") -> None: - ros_msg.disable_vision_foot_obstacle_avoidance = proto.disable_vision_foot_obstacle_avoidance - ros_msg.disable_vision_foot_constraint_avoidance = proto.disable_vision_foot_constraint_avoidance - ros_msg.disable_vision_body_obstacle_avoidance = proto.disable_vision_body_obstacle_avoidance - ros_msg.obstacle_avoidance_padding = proto.obstacle_avoidance_padding - ros_msg.disable_vision_foot_obstacle_body_assist = proto.disable_vision_foot_obstacle_body_assist - ros_msg.disable_vision_negative_obstacles = proto.disable_vision_negative_obstacles - - -def convert_bosdyn_msgs_obstacle_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ObstacleParams", proto: "bosdyn.api.spot.robot_command_pb2.ObstacleParams") -> None: - proto.Clear() - proto.disable_vision_foot_obstacle_avoidance = ros_msg.disable_vision_foot_obstacle_avoidance - proto.disable_vision_foot_constraint_avoidance = ros_msg.disable_vision_foot_constraint_avoidance - proto.disable_vision_body_obstacle_avoidance = ros_msg.disable_vision_body_obstacle_avoidance - proto.obstacle_avoidance_padding = ros_msg.obstacle_avoidance_padding - proto.disable_vision_foot_obstacle_body_assist = ros_msg.disable_vision_foot_obstacle_body_assist - proto.disable_vision_negative_obstacles = ros_msg.disable_vision_negative_obstacles - - -def convert_proto_to_bosdyn_msgs_terrain_params_grated_surfaces_mode(proto: "bosdyn.api.spot.robot_command_pb2.TerrainParams.GratedSurfacesMode", ros_msg: "bosdyn_msgs.msgs.TerrainParamsGratedSurfacesMode") -> None: - pass - - -def convert_bosdyn_msgs_terrain_params_grated_surfaces_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.TerrainParamsGratedSurfacesMode", proto: "bosdyn.api.spot.robot_command_pb2.TerrainParams.GratedSurfacesMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_terrain_params(proto: "bosdyn.api.spot.robot_command_pb2.TerrainParams", ros_msg: "bosdyn_msgs.msgs.TerrainParams") -> None: - ros_msg.ground_mu_hint = proto.ground_mu_hint.value - ros_msg.ground_mu_hint_is_set = proto.HasField("ground_mu_hint") - ros_msg.grated_surfaces_mode.value = proto.grated_surfaces_mode - - -def convert_bosdyn_msgs_terrain_params_to_proto(ros_msg: "bosdyn_msgs.msgs.TerrainParams", proto: "bosdyn.api.spot.robot_command_pb2.TerrainParams") -> None: - proto.Clear() - if ros_msg.ground_mu_hint_is_set: - convert_float64_to_proto(ros_msg.ground_mu_hint, proto.ground_mu_hint) - proto.grated_surfaces_mode = ros_msg.grated_surfaces_mode.value - - -def convert_proto_to_bosdyn_msgs_body_external_force_params_external_force_indicator(proto: "bosdyn.api.spot.robot_command_pb2.BodyExternalForceParams.ExternalForceIndicator", ros_msg: "bosdyn_msgs.msgs.BodyExternalForceParamsExternalForceIndicator") -> None: - pass - - -def convert_bosdyn_msgs_body_external_force_params_external_force_indicator_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyExternalForceParamsExternalForceIndicator", proto: "bosdyn.api.spot.robot_command_pb2.BodyExternalForceParams.ExternalForceIndicator") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_body_external_force_params(proto: "bosdyn.api.spot.robot_command_pb2.BodyExternalForceParams", ros_msg: "bosdyn_msgs.msgs.BodyExternalForceParams") -> None: - ros_msg.external_force_indicator.value = proto.external_force_indicator - ros_msg.frame_name = proto.frame_name - convert_proto_to_geometry_msgs_vector3(proto.external_force_override, ros_msg.external_force_override) - ros_msg.external_force_override_is_set = proto.HasField("external_force_override") - - -def convert_bosdyn_msgs_body_external_force_params_to_proto(ros_msg: "bosdyn_msgs.msgs.BodyExternalForceParams", proto: "bosdyn.api.spot.robot_command_pb2.BodyExternalForceParams") -> None: - proto.Clear() - proto.external_force_indicator = ros_msg.external_force_indicator.value - proto.frame_name = ros_msg.frame_name - if ros_msg.external_force_override_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.external_force_override, proto.external_force_override) - - -def convert_proto_to_bosdyn_msgs_spot_check_command_request_command(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandRequest.Command", ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandRequestCommand") -> None: - pass - - -def convert_bosdyn_msgs_spot_check_command_request_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandRequestCommand", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandRequest.Command") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_spot_check_command_request(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandRequest", ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.command.value = proto.command - - -def convert_bosdyn_msgs_spot_check_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandRequest", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.command = ros_msg.command.value - - -def convert_proto_to_bosdyn_msgs_spot_check_command_response_status(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandResponse.Status", ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_spot_check_command_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandResponseStatus", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_spot_check_command_response(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandResponse", ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - ros_msg.status.value = proto.status - ros_msg.message = proto.message - - -def convert_bosdyn_msgs_spot_check_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckCommandResponse", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - proto.status = ros_msg.status.value - proto.message = ros_msg.message - - -def convert_proto_to_bosdyn_msgs_spot_check_feedback_request(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_spot_check_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackRequest", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_spot_check_feedback_response_state(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse.State", ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponseState") -> None: - pass - - -def convert_bosdyn_msgs_spot_check_feedback_response_state_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponseState", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse.State") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_spot_check_feedback_response_error(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse.Error", ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponseError") -> None: - pass - - -def convert_bosdyn_msgs_spot_check_feedback_response_error_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponseError", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_spot_check_feedback_response(proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.state.value = proto.state - ros_msg.last_command.value = proto.last_command - ros_msg.error.value = proto.error - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsDepthPlaneSpotCheckResult - ros_msg.camera_results = [] - for _item in proto.camera_results: - ros_msg.camera_results.append(KeyStringValueBosdynMsgsDepthPlaneSpotCheckResult()) - ros_msg.camera_results[-1].key = _item - convert_proto_to_bosdyn_msgs_depth_plane_spot_check_result(proto.camera_results[_item], ros_msg.camera_results[-1].value) - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsLoadCellSpotCheckResult - ros_msg.load_cell_results = [] - for _item in proto.load_cell_results: - ros_msg.load_cell_results.append(KeyStringValueBosdynMsgsLoadCellSpotCheckResult()) - ros_msg.load_cell_results[-1].key = _item - convert_proto_to_bosdyn_msgs_load_cell_spot_check_result(proto.load_cell_results[_item], ros_msg.load_cell_results[-1].value) - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsJointKinematicCheckResult - ros_msg.kinematic_cal_results = [] - for _item in proto.kinematic_cal_results: - ros_msg.kinematic_cal_results.append(KeyStringValueBosdynMsgsJointKinematicCheckResult()) - ros_msg.kinematic_cal_results[-1].key = _item - convert_proto_to_bosdyn_msgs_joint_kinematic_check_result(proto.kinematic_cal_results[_item], ros_msg.kinematic_cal_results[-1].value) - convert_proto_to_bosdyn_msgs_payload_check_result(proto.payload_result, ros_msg.payload_result) - ros_msg.payload_result_is_set = proto.HasField("payload_result") - from bosdyn_msgs.msg import KeyStringValueBosdynMsgsHipRangeOfMotionResult - ros_msg.hip_range_of_motion_results = [] - for _item in proto.hip_range_of_motion_results: - ros_msg.hip_range_of_motion_results.append(KeyStringValueBosdynMsgsHipRangeOfMotionResult()) - ros_msg.hip_range_of_motion_results[-1].key = _item - convert_proto_to_bosdyn_msgs_hip_range_of_motion_result(proto.hip_range_of_motion_results[_item], ros_msg.hip_range_of_motion_results[-1].value) - ros_msg.progress = proto.progress - convert_proto_to_builtin_interfaces_time(proto.last_cal_timestamp, ros_msg.last_cal_timestamp) - ros_msg.last_cal_timestamp_is_set = proto.HasField("last_cal_timestamp") - - -def convert_bosdyn_msgs_spot_check_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SpotCheckFeedbackResponse", proto: "bosdyn.api.spot.spot_check_pb2.SpotCheckFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.state = ros_msg.state.value - proto.last_command = ros_msg.last_command.value - proto.error = ros_msg.error.value - for _item in ros_msg.camera_results: - convert_bosdyn_msgs_depth_plane_spot_check_result_to_proto(_item.value, proto.camera_results[_item.key]) - for _item in ros_msg.load_cell_results: - convert_bosdyn_msgs_load_cell_spot_check_result_to_proto(_item.value, proto.load_cell_results[_item.key]) - for _item in ros_msg.kinematic_cal_results: - convert_bosdyn_msgs_joint_kinematic_check_result_to_proto(_item.value, proto.kinematic_cal_results[_item.key]) - if ros_msg.payload_result_is_set: - convert_bosdyn_msgs_payload_check_result_to_proto(ros_msg.payload_result, proto.payload_result) - for _item in ros_msg.hip_range_of_motion_results: - convert_bosdyn_msgs_hip_range_of_motion_result_to_proto(_item.value, proto.hip_range_of_motion_results[_item.key]) - proto.progress = ros_msg.progress - if ros_msg.last_cal_timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.last_cal_timestamp, proto.last_cal_timestamp) - - -def convert_proto_to_bosdyn_msgs_depth_plane_spot_check_result_status(proto: "bosdyn.api.spot.spot_check_pb2.DepthPlaneSpotCheckResult.Status", ros_msg: "bosdyn_msgs.msgs.DepthPlaneSpotCheckResultStatus") -> None: - pass - - -def convert_bosdyn_msgs_depth_plane_spot_check_result_status_to_proto(ros_msg: "bosdyn_msgs.msgs.DepthPlaneSpotCheckResultStatus", proto: "bosdyn.api.spot.spot_check_pb2.DepthPlaneSpotCheckResult.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_depth_plane_spot_check_result(proto: "bosdyn.api.spot.spot_check_pb2.DepthPlaneSpotCheckResult", ros_msg: "bosdyn_msgs.msgs.DepthPlaneSpotCheckResult") -> None: - ros_msg.status.value = proto.status - ros_msg.severity_score = proto.severity_score - - -def convert_bosdyn_msgs_depth_plane_spot_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.DepthPlaneSpotCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.DepthPlaneSpotCheckResult") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.severity_score = ros_msg.severity_score - - -def convert_proto_to_bosdyn_msgs_payload_check_result_error(proto: "bosdyn.api.spot.spot_check_pb2.PayloadCheckResult.Error", ros_msg: "bosdyn_msgs.msgs.PayloadCheckResultError") -> None: - pass - - -def convert_bosdyn_msgs_payload_check_result_error_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadCheckResultError", proto: "bosdyn.api.spot.spot_check_pb2.PayloadCheckResult.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_payload_check_result(proto: "bosdyn.api.spot.spot_check_pb2.PayloadCheckResult", ros_msg: "bosdyn_msgs.msgs.PayloadCheckResult") -> None: - ros_msg.error.value = proto.error - ros_msg.extra_payload = proto.extra_payload - - -def convert_bosdyn_msgs_payload_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.PayloadCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.PayloadCheckResult") -> None: - proto.Clear() - proto.error = ros_msg.error.value - proto.extra_payload = ros_msg.extra_payload - - -def convert_proto_to_bosdyn_msgs_load_cell_spot_check_result_error(proto: "bosdyn.api.spot.spot_check_pb2.LoadCellSpotCheckResult.Error", ros_msg: "bosdyn_msgs.msgs.LoadCellSpotCheckResultError") -> None: - pass - - -def convert_bosdyn_msgs_load_cell_spot_check_result_error_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadCellSpotCheckResultError", proto: "bosdyn.api.spot.spot_check_pb2.LoadCellSpotCheckResult.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_load_cell_spot_check_result(proto: "bosdyn.api.spot.spot_check_pb2.LoadCellSpotCheckResult", ros_msg: "bosdyn_msgs.msgs.LoadCellSpotCheckResult") -> None: - ros_msg.error.value = proto.error - ros_msg.zero = proto.zero - ros_msg.old_zero = proto.old_zero - - -def convert_bosdyn_msgs_load_cell_spot_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadCellSpotCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.LoadCellSpotCheckResult") -> None: - proto.Clear() - proto.error = ros_msg.error.value - proto.zero = ros_msg.zero - proto.old_zero = ros_msg.old_zero - - -def convert_proto_to_bosdyn_msgs_joint_kinematic_check_result_error(proto: "bosdyn.api.spot.spot_check_pb2.JointKinematicCheckResult.Error", ros_msg: "bosdyn_msgs.msgs.JointKinematicCheckResultError") -> None: - pass - - -def convert_bosdyn_msgs_joint_kinematic_check_result_error_to_proto(ros_msg: "bosdyn_msgs.msgs.JointKinematicCheckResultError", proto: "bosdyn.api.spot.spot_check_pb2.JointKinematicCheckResult.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_joint_kinematic_check_result(proto: "bosdyn.api.spot.spot_check_pb2.JointKinematicCheckResult", ros_msg: "bosdyn_msgs.msgs.JointKinematicCheckResult") -> None: - ros_msg.error.value = proto.error - ros_msg.offset = proto.offset - ros_msg.old_offset = proto.old_offset - ros_msg.health_score = proto.health_score - - -def convert_bosdyn_msgs_joint_kinematic_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.JointKinematicCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.JointKinematicCheckResult") -> None: - proto.Clear() - proto.error = ros_msg.error.value - proto.offset = ros_msg.offset - proto.old_offset = ros_msg.old_offset - proto.health_score = ros_msg.health_score - - -def convert_proto_to_bosdyn_msgs_foot_height_check_result_status(proto: "bosdyn.api.spot.spot_check_pb2.FootHeightCheckResult.Status", ros_msg: "bosdyn_msgs.msgs.FootHeightCheckResultStatus") -> None: - pass - - -def convert_bosdyn_msgs_foot_height_check_result_status_to_proto(ros_msg: "bosdyn_msgs.msgs.FootHeightCheckResultStatus", proto: "bosdyn.api.spot.spot_check_pb2.FootHeightCheckResult.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_foot_height_check_result(proto: "bosdyn.api.spot.spot_check_pb2.FootHeightCheckResult", ros_msg: "bosdyn_msgs.msgs.FootHeightCheckResult") -> None: - ros_msg.status.value = proto.status - ros_msg.foot_height_error_from_mean = proto.foot_height_error_from_mean - - -def convert_bosdyn_msgs_foot_height_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.FootHeightCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.FootHeightCheckResult") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.foot_height_error_from_mean = ros_msg.foot_height_error_from_mean - - -def convert_proto_to_bosdyn_msgs_leg_pair_check_result_status(proto: "bosdyn.api.spot.spot_check_pb2.LegPairCheckResult.Status", ros_msg: "bosdyn_msgs.msgs.LegPairCheckResultStatus") -> None: - pass - - -def convert_bosdyn_msgs_leg_pair_check_result_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LegPairCheckResultStatus", proto: "bosdyn.api.spot.spot_check_pb2.LegPairCheckResult.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_leg_pair_check_result(proto: "bosdyn.api.spot.spot_check_pb2.LegPairCheckResult", ros_msg: "bosdyn_msgs.msgs.LegPairCheckResult") -> None: - ros_msg.status.value = proto.status - ros_msg.leg_pair_distance_change = proto.leg_pair_distance_change - - -def convert_bosdyn_msgs_leg_pair_check_result_to_proto(ros_msg: "bosdyn_msgs.msgs.LegPairCheckResult", proto: "bosdyn.api.spot.spot_check_pb2.LegPairCheckResult") -> None: - proto.Clear() - proto.status = ros_msg.status.value - proto.leg_pair_distance_change = ros_msg.leg_pair_distance_change - - -def convert_proto_to_bosdyn_msgs_hip_range_of_motion_result_error(proto: "bosdyn.api.spot.spot_check_pb2.HipRangeOfMotionResult.Error", ros_msg: "bosdyn_msgs.msgs.HipRangeOfMotionResultError") -> None: - pass - - -def convert_bosdyn_msgs_hip_range_of_motion_result_error_to_proto(ros_msg: "bosdyn_msgs.msgs.HipRangeOfMotionResultError", proto: "bosdyn.api.spot.spot_check_pb2.HipRangeOfMotionResult.Error") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_hip_range_of_motion_result(proto: "bosdyn.api.spot.spot_check_pb2.HipRangeOfMotionResult", ros_msg: "bosdyn_msgs.msgs.HipRangeOfMotionResult") -> None: - ros_msg.error.value = proto.error - ros_msg.hx = [] - for _item in proto.hx: - ros_msg.hx.append(_item) - ros_msg.hy = [] - for _item in proto.hy: - ros_msg.hy.append(_item) - - -def convert_bosdyn_msgs_hip_range_of_motion_result_to_proto(ros_msg: "bosdyn_msgs.msgs.HipRangeOfMotionResult", proto: "bosdyn.api.spot.spot_check_pb2.HipRangeOfMotionResult") -> None: - proto.Clear() - proto.error = ros_msg.error.value - del proto.hx[:] - for _item in ros_msg.hx: - proto.hx.append(_item) - del proto.hy[:] - for _item in ros_msg.hy: - proto.hy.append(_item) - - -def convert_proto_to_bosdyn_msgs_camera_calibration_command_request_command(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandRequest.Command", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandRequestCommand") -> None: - pass - - -def convert_bosdyn_msgs_camera_calibration_command_request_command_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandRequestCommand", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandRequest.Command") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_camera_calibration_command_request(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandRequest", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease(proto.lease, ros_msg.lease) - ros_msg.lease_is_set = proto.HasField("lease") - ros_msg.command.value = proto.command - - -def convert_bosdyn_msgs_camera_calibration_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandRequest", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_is_set: - convert_bosdyn_msgs_lease_to_proto(ros_msg.lease, proto.lease) - proto.command = ros_msg.command.value - - -def convert_proto_to_bosdyn_msgs_camera_calibration_command_response(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandResponse", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_lease_use_result(proto.lease_use_result, ros_msg.lease_use_result) - ros_msg.lease_use_result_is_set = proto.HasField("lease_use_result") - - -def convert_bosdyn_msgs_camera_calibration_command_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationCommandResponse", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationCommandResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.lease_use_result_is_set: - convert_bosdyn_msgs_lease_use_result_to_proto(ros_msg.lease_use_result, proto.lease_use_result) - - -def convert_proto_to_bosdyn_msgs_camera_calibration_feedback_request(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackRequest", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_camera_calibration_feedback_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackRequest", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_camera_calibration_feedback_response_status(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackResponse.Status", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_camera_calibration_feedback_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackResponseStatus", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_camera_calibration_feedback_response(proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackResponse", ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.progress = proto.progress - - -def convert_bosdyn_msgs_camera_calibration_feedback_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraCalibrationFeedbackResponse", proto: "bosdyn.api.spot.spot_check_pb2.CameraCalibrationFeedbackResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.progress = ros_msg.progress - - -def convert_proto_to_bosdyn_msgs_get_led_brightness_request(proto: "bosdyn.api.spot_cam.LED_pb2.GetLEDBrightnessRequest", ros_msg: "bosdyn_msgs.msgs.GetLEDBrightnessRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_led_brightness_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLEDBrightnessRequest", proto: "bosdyn.api.spot_cam.LED_pb2.GetLEDBrightnessRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_led_brightness_response(proto: "bosdyn.api.spot_cam.LED_pb2.GetLEDBrightnessResponse", ros_msg: "bosdyn_msgs.msgs.GetLEDBrightnessResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.brightnesses = [] - for _item in proto.brightnesses: - ros_msg.brightnesses.append(_item) - - -def convert_bosdyn_msgs_get_led_brightness_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetLEDBrightnessResponse", proto: "bosdyn.api.spot_cam.LED_pb2.GetLEDBrightnessResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.brightnesses[:] - for _item in ros_msg.brightnesses: - proto.brightnesses.append(_item) - - -def convert_proto_to_bosdyn_msgs_set_led_brightness_request(proto: "bosdyn.api.spot_cam.LED_pb2.SetLEDBrightnessRequest", ros_msg: "bosdyn_msgs.msgs.SetLEDBrightnessRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import KeyInt32ValueFloat32 - ros_msg.brightnesses = [] - for _item in proto.brightnesses: - ros_msg.brightnesses.append(KeyInt32ValueFloat32()) - ros_msg.brightnesses[-1].key = _item - ros_msg.brightnesses[-1].value = proto.brightnesses[_item] - - -def convert_bosdyn_msgs_set_led_brightness_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLEDBrightnessRequest", proto: "bosdyn.api.spot_cam.LED_pb2.SetLEDBrightnessRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - for _item in ros_msg.brightnesses: - proto.brightnesses[_item.key] = _item.value - - -def convert_proto_to_bosdyn_msgs_set_led_brightness_response(proto: "bosdyn.api.spot_cam.LED_pb2.SetLEDBrightnessResponse", ros_msg: "bosdyn_msgs.msgs.SetLEDBrightnessResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_led_brightness_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetLEDBrightnessResponse", proto: "bosdyn.api.spot_cam.LED_pb2.SetLEDBrightnessResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_sound(proto: "bosdyn.api.spot_cam.audio_pb2.Sound", ros_msg: "bosdyn_msgs.msgs.Sound") -> None: - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_sound_to_proto(ros_msg: "bosdyn_msgs.msgs.Sound", proto: "bosdyn.api.spot_cam.audio_pb2.Sound") -> None: - proto.Clear() - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_list_sounds_request(proto: "bosdyn.api.spot_cam.audio_pb2.ListSoundsRequest", ros_msg: "bosdyn_msgs.msgs.ListSoundsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_sounds_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListSoundsRequest", proto: "bosdyn.api.spot_cam.audio_pb2.ListSoundsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_sounds_response(proto: "bosdyn.api.spot_cam.audio_pb2.ListSoundsResponse", ros_msg: "bosdyn_msgs.msgs.ListSoundsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Sound - ros_msg.sounds = [] - for _item in proto.sounds: - ros_msg.sounds.append(Sound()) - convert_proto_to_bosdyn_msgs_sound(_item, ros_msg.sounds[-1]) - - -def convert_bosdyn_msgs_list_sounds_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListSoundsResponse", proto: "bosdyn.api.spot_cam.audio_pb2.ListSoundsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.sounds[:] - for _item in ros_msg.sounds: - convert_bosdyn_msgs_sound_to_proto(_item, proto.sounds.add()) - - -def convert_proto_to_bosdyn_msgs_set_volume_request(proto: "bosdyn.api.spot_cam.audio_pb2.SetVolumeRequest", ros_msg: "bosdyn_msgs.msgs.SetVolumeRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.volume = proto.volume - - -def convert_bosdyn_msgs_set_volume_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetVolumeRequest", proto: "bosdyn.api.spot_cam.audio_pb2.SetVolumeRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.volume = ros_msg.volume - - -def convert_proto_to_bosdyn_msgs_set_volume_response(proto: "bosdyn.api.spot_cam.audio_pb2.SetVolumeResponse", ros_msg: "bosdyn_msgs.msgs.SetVolumeResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_volume_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetVolumeResponse", proto: "bosdyn.api.spot_cam.audio_pb2.SetVolumeResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_volume_request(proto: "bosdyn.api.spot_cam.audio_pb2.GetVolumeRequest", ros_msg: "bosdyn_msgs.msgs.GetVolumeRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_volume_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVolumeRequest", proto: "bosdyn.api.spot_cam.audio_pb2.GetVolumeRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_volume_response(proto: "bosdyn.api.spot_cam.audio_pb2.GetVolumeResponse", ros_msg: "bosdyn_msgs.msgs.GetVolumeResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.volume = proto.volume - - -def convert_bosdyn_msgs_get_volume_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVolumeResponse", proto: "bosdyn.api.spot_cam.audio_pb2.GetVolumeResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.volume = ros_msg.volume - - -def convert_proto_to_bosdyn_msgs_play_sound_request(proto: "bosdyn.api.spot_cam.audio_pb2.PlaySoundRequest", ros_msg: "bosdyn_msgs.msgs.PlaySoundRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_sound(proto.sound, ros_msg.sound) - ros_msg.sound_is_set = proto.HasField("sound") - ros_msg.gain = proto.gain.value - ros_msg.gain_is_set = proto.HasField("gain") - - -def convert_bosdyn_msgs_play_sound_request_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaySoundRequest", proto: "bosdyn.api.spot_cam.audio_pb2.PlaySoundRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.sound_is_set: - convert_bosdyn_msgs_sound_to_proto(ros_msg.sound, proto.sound) - if ros_msg.gain_is_set: - convert_float32_to_proto(ros_msg.gain, proto.gain) - - -def convert_proto_to_bosdyn_msgs_play_sound_response(proto: "bosdyn.api.spot_cam.audio_pb2.PlaySoundResponse", ros_msg: "bosdyn_msgs.msgs.PlaySoundResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_play_sound_response_to_proto(ros_msg: "bosdyn_msgs.msgs.PlaySoundResponse", proto: "bosdyn.api.spot_cam.audio_pb2.PlaySoundResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_delete_sound_request(proto: "bosdyn.api.spot_cam.audio_pb2.DeleteSoundRequest", ros_msg: "bosdyn_msgs.msgs.DeleteSoundRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_sound(proto.sound, ros_msg.sound) - ros_msg.sound_is_set = proto.HasField("sound") - - -def convert_bosdyn_msgs_delete_sound_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteSoundRequest", proto: "bosdyn.api.spot_cam.audio_pb2.DeleteSoundRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.sound_is_set: - convert_bosdyn_msgs_sound_to_proto(ros_msg.sound, proto.sound) - - -def convert_proto_to_bosdyn_msgs_delete_sound_response(proto: "bosdyn.api.spot_cam.audio_pb2.DeleteSoundResponse", ros_msg: "bosdyn_msgs.msgs.DeleteSoundResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_delete_sound_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteSoundResponse", proto: "bosdyn.api.spot_cam.audio_pb2.DeleteSoundResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_load_sound_request(proto: "bosdyn.api.spot_cam.audio_pb2.LoadSoundRequest", ros_msg: "bosdyn_msgs.msgs.LoadSoundRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_sound(proto.sound, ros_msg.sound) - ros_msg.sound_is_set = proto.HasField("sound") - convert_proto_to_bosdyn_msgs_data_chunk(proto.data, ros_msg.data) - ros_msg.data_is_set = proto.HasField("data") - - -def convert_bosdyn_msgs_load_sound_request_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadSoundRequest", proto: "bosdyn.api.spot_cam.audio_pb2.LoadSoundRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.sound_is_set: - convert_bosdyn_msgs_sound_to_proto(ros_msg.sound, proto.sound) - if ros_msg.data_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.data, proto.data) - - -def convert_proto_to_bosdyn_msgs_load_sound_response(proto: "bosdyn.api.spot_cam.audio_pb2.LoadSoundResponse", ros_msg: "bosdyn_msgs.msgs.LoadSoundResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_load_sound_response_to_proto(ros_msg: "bosdyn_msgs.msgs.LoadSoundResponse", proto: "bosdyn.api.spot_cam.audio_pb2.LoadSoundResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_audio_capture_channel(proto: "bosdyn.api.spot_cam.audio_pb2.AudioCaptureChannel", ros_msg: "bosdyn_msgs.msgs.AudioCaptureChannel") -> None: - pass - - -def convert_bosdyn_msgs_audio_capture_channel_to_proto(ros_msg: "bosdyn_msgs.msgs.AudioCaptureChannel", proto: "bosdyn.api.spot_cam.audio_pb2.AudioCaptureChannel") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_set_audio_capture_channel_request(proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureChannelRequest", ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureChannelRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.channel.value = proto.channel - - -def convert_bosdyn_msgs_set_audio_capture_channel_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureChannelRequest", proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureChannelRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.channel = ros_msg.channel.value - - -def convert_proto_to_bosdyn_msgs_set_audio_capture_channel_response(proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureChannelResponse", ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureChannelResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_audio_capture_channel_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureChannelResponse", proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureChannelResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_audio_capture_channel_request(proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureChannelRequest", ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureChannelRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_audio_capture_channel_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureChannelRequest", proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureChannelRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_audio_capture_channel_response(proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureChannelResponse", ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureChannelResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.channel.value = proto.channel - - -def convert_bosdyn_msgs_get_audio_capture_channel_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureChannelResponse", proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureChannelResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.channel = ros_msg.channel.value - - -def convert_proto_to_bosdyn_msgs_set_audio_capture_gain_request(proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureGainRequest", ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureGainRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.channel.value = proto.channel - ros_msg.gain = proto.gain - - -def convert_bosdyn_msgs_set_audio_capture_gain_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureGainRequest", proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureGainRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.channel = ros_msg.channel.value - proto.gain = ros_msg.gain - - -def convert_proto_to_bosdyn_msgs_set_audio_capture_gain_response(proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureGainResponse", ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureGainResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_audio_capture_gain_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetAudioCaptureGainResponse", proto: "bosdyn.api.spot_cam.audio_pb2.SetAudioCaptureGainResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_audio_capture_gain_request(proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureGainRequest", ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureGainRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.channel.value = proto.channel - - -def convert_bosdyn_msgs_get_audio_capture_gain_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureGainRequest", proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureGainRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.channel = ros_msg.channel.value - - -def convert_proto_to_bosdyn_msgs_get_audio_capture_gain_response(proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureGainResponse", ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureGainResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.gain = proto.gain - - -def convert_bosdyn_msgs_get_audio_capture_gain_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetAudioCaptureGainResponse", proto: "bosdyn.api.spot_cam.audio_pb2.GetAudioCaptureGainResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.gain = ros_msg.gain - - -def convert_proto_to_bosdyn_msgs_camera_pinhole_intrinsics(proto: "bosdyn.api.spot_cam.camera_pb2.Camera.PinholeIntrinsics", ros_msg: "bosdyn_msgs.msgs.CameraPinholeIntrinsics") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.focal_length, ros_msg.focal_length) - ros_msg.focal_length_is_set = proto.HasField("focal_length") - convert_proto_to_bosdyn_msgs_vec2(proto.center_point, ros_msg.center_point) - ros_msg.center_point_is_set = proto.HasField("center_point") - ros_msg.k1 = proto.k1 - ros_msg.k2 = proto.k2 - ros_msg.k3 = proto.k3 - ros_msg.k4 = proto.k4 - - -def convert_bosdyn_msgs_camera_pinhole_intrinsics_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraPinholeIntrinsics", proto: "bosdyn.api.spot_cam.camera_pb2.Camera.PinholeIntrinsics") -> None: - proto.Clear() - if ros_msg.focal_length_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.focal_length, proto.focal_length) - if ros_msg.center_point_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.center_point, proto.center_point) - proto.k1 = ros_msg.k1 - proto.k2 = ros_msg.k2 - proto.k3 = ros_msg.k3 - proto.k4 = ros_msg.k4 - - -def convert_proto_to_bosdyn_msgs_camera_spherical_limits(proto: "bosdyn.api.spot_cam.camera_pb2.Camera.SphericalLimits", ros_msg: "bosdyn_msgs.msgs.CameraSphericalLimits") -> None: - convert_proto_to_bosdyn_msgs_vec2(proto.min_angle, ros_msg.min_angle) - ros_msg.min_angle_is_set = proto.HasField("min_angle") - convert_proto_to_bosdyn_msgs_vec2(proto.max_angle, ros_msg.max_angle) - ros_msg.max_angle_is_set = proto.HasField("max_angle") - - -def convert_bosdyn_msgs_camera_spherical_limits_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraSphericalLimits", proto: "bosdyn.api.spot_cam.camera_pb2.Camera.SphericalLimits") -> None: - proto.Clear() - if ros_msg.min_angle_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.min_angle, proto.min_angle) - if ros_msg.max_angle_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.max_angle, proto.max_angle) - - -def convert_proto_to_bosdyn_msgs_camera_one_of_intrinsics(proto: "bosdyn.api.spot_cam.camera_pb2.Camera", ros_msg: "bosdyn_msgs.msgs.CameraOneOfIntrinsics") -> None: - if proto.HasField("pinhole"): - ros_msg.intrinsics_choice = ros_msg.INTRINSICS_PINHOLE_SET - convert_proto_to_bosdyn_msgs_camera_pinhole_intrinsics(proto.pinhole, ros_msg.pinhole) - if proto.HasField("spherical"): - ros_msg.intrinsics_choice = ros_msg.INTRINSICS_SPHERICAL_SET - convert_proto_to_bosdyn_msgs_camera_spherical_limits(proto.spherical, ros_msg.spherical) - - -def convert_bosdyn_msgs_camera_one_of_intrinsics_to_proto(ros_msg: "bosdyn_msgs.msgs.CameraOneOfIntrinsics", proto: "bosdyn.api.spot_cam.camera_pb2.Camera") -> None: - proto.ClearField("intrinsics") - if ros_msg.intrinsics_choice == ros_msg.INTRINSICS_PINHOLE_SET: - convert_bosdyn_msgs_camera_pinhole_intrinsics_to_proto(ros_msg.pinhole, proto.pinhole) - if ros_msg.intrinsics_choice == ros_msg.INTRINSICS_SPHERICAL_SET: - convert_bosdyn_msgs_camera_spherical_limits_to_proto(ros_msg.spherical, proto.spherical) - - -def convert_proto_to_bosdyn_msgs_camera(proto: "bosdyn.api.spot_cam.camera_pb2.Camera", ros_msg: "bosdyn_msgs.msgs.Camera") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_vec2(proto.resolution, ros_msg.resolution) - ros_msg.resolution_is_set = proto.HasField("resolution") - ros_msg.base_frame_name = proto.base_frame_name - convert_proto_to_geometry_msgs_pose(proto.base_tform_sensor, ros_msg.base_tform_sensor) - ros_msg.base_tform_sensor_is_set = proto.HasField("base_tform_sensor") - convert_proto_to_bosdyn_msgs_camera_one_of_intrinsics(proto, ros_msg.intrinsics) - - -def convert_bosdyn_msgs_camera_to_proto(ros_msg: "bosdyn_msgs.msgs.Camera", proto: "bosdyn.api.spot_cam.camera_pb2.Camera") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.resolution_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.resolution, proto.resolution) - proto.base_frame_name = ros_msg.base_frame_name - if ros_msg.base_tform_sensor_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.base_tform_sensor, proto.base_tform_sensor) - convert_bosdyn_msgs_camera_one_of_intrinsics_to_proto(ros_msg.intrinsics, proto) - - -def convert_proto_to_bosdyn_msgs_screen_description(proto: "bosdyn.api.spot_cam.compositor_pb2.ScreenDescription", ros_msg: "bosdyn_msgs.msgs.ScreenDescription") -> None: - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_screen_description_to_proto(ros_msg: "bosdyn_msgs.msgs.ScreenDescription", proto: "bosdyn.api.spot_cam.compositor_pb2.ScreenDescription") -> None: - proto.Clear() - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_get_screen_request(proto: "bosdyn.api.spot_cam.compositor_pb2.GetScreenRequest", ros_msg: "bosdyn_msgs.msgs.GetScreenRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_screen_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetScreenRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.GetScreenRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_screen_response(proto: "bosdyn.api.spot_cam.compositor_pb2.GetScreenResponse", ros_msg: "bosdyn_msgs.msgs.GetScreenResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_get_screen_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetScreenResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.GetScreenResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_get_visible_cameras_request(proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasRequest", ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_visible_cameras_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_visible_cameras_response_stream_window(proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse.Stream.Window", ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponseStreamWindow") -> None: - ros_msg.xoffset = proto.xoffset - ros_msg.yoffset = proto.yoffset - ros_msg.width = proto.width - ros_msg.height = proto.height - - -def convert_bosdyn_msgs_get_visible_cameras_response_stream_window_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponseStreamWindow", proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse.Stream.Window") -> None: - proto.Clear() - proto.xoffset = ros_msg.xoffset - proto.yoffset = ros_msg.yoffset - proto.width = ros_msg.width - proto.height = ros_msg.height - - -def convert_proto_to_bosdyn_msgs_get_visible_cameras_response_stream(proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse.Stream", ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponseStream") -> None: - convert_proto_to_bosdyn_msgs_get_visible_cameras_response_stream_window(proto.window, ros_msg.window) - ros_msg.window_is_set = proto.HasField("window") - convert_proto_to_bosdyn_msgs_camera(proto.camera, ros_msg.camera) - ros_msg.camera_is_set = proto.HasField("camera") - - -def convert_bosdyn_msgs_get_visible_cameras_response_stream_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponseStream", proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse.Stream") -> None: - proto.Clear() - if ros_msg.window_is_set: - convert_bosdyn_msgs_get_visible_cameras_response_stream_window_to_proto(ros_msg.window, proto.window) - if ros_msg.camera_is_set: - convert_bosdyn_msgs_camera_to_proto(ros_msg.camera, proto.camera) - - -def convert_proto_to_bosdyn_msgs_get_visible_cameras_response(proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse", ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import GetVisibleCamerasResponseStream - ros_msg.streams = [] - for _item in proto.streams: - ros_msg.streams.append(GetVisibleCamerasResponseStream()) - convert_proto_to_bosdyn_msgs_get_visible_cameras_response_stream(_item, ros_msg.streams[-1]) - - -def convert_bosdyn_msgs_get_visible_cameras_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetVisibleCamerasResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.GetVisibleCamerasResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.streams[:] - for _item in ros_msg.streams: - convert_bosdyn_msgs_get_visible_cameras_response_stream_to_proto(_item, proto.streams.add()) - - -def convert_proto_to_bosdyn_msgs_list_screens_request(proto: "bosdyn.api.spot_cam.compositor_pb2.ListScreensRequest", ros_msg: "bosdyn_msgs.msgs.ListScreensRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_screens_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListScreensRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.ListScreensRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_screens_response(proto: "bosdyn.api.spot_cam.compositor_pb2.ListScreensResponse", ros_msg: "bosdyn_msgs.msgs.ListScreensResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ScreenDescription - ros_msg.screens = [] - for _item in proto.screens: - ros_msg.screens.append(ScreenDescription()) - convert_proto_to_bosdyn_msgs_screen_description(_item, ros_msg.screens[-1]) - - -def convert_bosdyn_msgs_list_screens_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListScreensResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.ListScreensResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.screens[:] - for _item in ros_msg.screens: - convert_bosdyn_msgs_screen_description_to_proto(_item, proto.screens.add()) - - -def convert_proto_to_bosdyn_msgs_set_screen_request(proto: "bosdyn.api.spot_cam.compositor_pb2.SetScreenRequest", ros_msg: "bosdyn_msgs.msgs.SetScreenRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_set_screen_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetScreenRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.SetScreenRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_set_screen_response(proto: "bosdyn.api.spot_cam.compositor_pb2.SetScreenResponse", ros_msg: "bosdyn_msgs.msgs.SetScreenResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.name = proto.name - - -def convert_bosdyn_msgs_set_screen_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetScreenResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.SetScreenResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.name = ros_msg.name - - -def convert_proto_to_bosdyn_msgs_ir_color_map_color_map(proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap.ColorMap", ros_msg: "bosdyn_msgs.msgs.IrColorMapColorMap") -> None: - pass - - -def convert_bosdyn_msgs_ir_color_map_color_map_to_proto(ros_msg: "bosdyn_msgs.msgs.IrColorMapColorMap", proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap.ColorMap") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ir_color_map_scaling_pair(proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap.ScalingPair", ros_msg: "bosdyn_msgs.msgs.IrColorMapScalingPair") -> None: - ros_msg.min = proto.min - ros_msg.max = proto.max - - -def convert_bosdyn_msgs_ir_color_map_scaling_pair_to_proto(ros_msg: "bosdyn_msgs.msgs.IrColorMapScalingPair", proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap.ScalingPair") -> None: - proto.Clear() - proto.min = ros_msg.min - proto.max = ros_msg.max - - -def convert_proto_to_bosdyn_msgs_ir_color_map(proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap", ros_msg: "bosdyn_msgs.msgs.IrColorMap") -> None: - ros_msg.colormap.value = proto.colormap - convert_proto_to_bosdyn_msgs_ir_color_map_scaling_pair(proto.scale, ros_msg.scale) - ros_msg.scale_is_set = proto.HasField("scale") - ros_msg.auto_scale = proto.auto_scale.value - ros_msg.auto_scale_is_set = proto.HasField("auto_scale") - - -def convert_bosdyn_msgs_ir_color_map_to_proto(ros_msg: "bosdyn_msgs.msgs.IrColorMap", proto: "bosdyn.api.spot_cam.compositor_pb2.IrColorMap") -> None: - proto.Clear() - proto.colormap = ros_msg.colormap.value - if ros_msg.scale_is_set: - convert_bosdyn_msgs_ir_color_map_scaling_pair_to_proto(ros_msg.scale, proto.scale) - if ros_msg.auto_scale_is_set: - convert_bool_to_proto(ros_msg.auto_scale, proto.auto_scale) - - -def convert_proto_to_bosdyn_msgs_set_ir_colormap_request(proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrColormapRequest", ros_msg: "bosdyn_msgs.msgs.SetIrColormapRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ir_color_map(proto.map, ros_msg.map) - ros_msg.map_is_set = proto.HasField("map") - - -def convert_bosdyn_msgs_set_ir_colormap_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetIrColormapRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrColormapRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.map_is_set: - convert_bosdyn_msgs_ir_color_map_to_proto(ros_msg.map, proto.map) - - -def convert_proto_to_bosdyn_msgs_set_ir_colormap_response(proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrColormapResponse", ros_msg: "bosdyn_msgs.msgs.SetIrColormapResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_ir_colormap_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetIrColormapResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrColormapResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ir_colormap_request(proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrColormapRequest", ros_msg: "bosdyn_msgs.msgs.GetIrColormapRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_ir_colormap_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetIrColormapRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrColormapRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ir_colormap_response(proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrColormapResponse", ros_msg: "bosdyn_msgs.msgs.GetIrColormapResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ir_color_map(proto.map, ros_msg.map) - ros_msg.map_is_set = proto.HasField("map") - - -def convert_bosdyn_msgs_get_ir_colormap_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetIrColormapResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrColormapResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.map_is_set: - convert_bosdyn_msgs_ir_color_map_to_proto(ros_msg.map, proto.map) - - -def convert_proto_to_bosdyn_msgs_ir_meter_overlay_normalized_coordinates(proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.NormalizedCoordinates", ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayNormalizedCoordinates") -> None: - ros_msg.x = proto.x - ros_msg.y = proto.y - - -def convert_bosdyn_msgs_ir_meter_overlay_normalized_coordinates_to_proto(ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayNormalizedCoordinates", proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.NormalizedCoordinates") -> None: - proto.Clear() - proto.x = ros_msg.x - proto.y = ros_msg.y - - -def convert_proto_to_bosdyn_msgs_ir_meter_overlay_temp_unit_temp_unit_type(proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.TempUnit.TempUnitType", ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayTempUnitTempUnitType") -> None: - pass - - -def convert_bosdyn_msgs_ir_meter_overlay_temp_unit_temp_unit_type_to_proto(ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayTempUnitTempUnitType", proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.TempUnit.TempUnitType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ir_meter_overlay_temp_unit(proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.TempUnit", ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayTempUnit") -> None: - ros_msg.value.value = proto.value - - -def convert_bosdyn_msgs_ir_meter_overlay_temp_unit_to_proto(ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayTempUnit", proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.TempUnit") -> None: - proto.Clear() - proto.value = ros_msg.value.value - - -def convert_proto_to_bosdyn_msgs_ir_meter_overlay_delta_pair(proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.DeltaPair", ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayDeltaPair") -> None: - ros_msg.a = proto.a - ros_msg.b = proto.b - - -def convert_bosdyn_msgs_ir_meter_overlay_delta_pair_to_proto(ros_msg: "bosdyn_msgs.msgs.IrMeterOverlayDeltaPair", proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay.DeltaPair") -> None: - proto.Clear() - proto.a = ros_msg.a - proto.b = ros_msg.b - - -def convert_proto_to_bosdyn_msgs_ir_meter_overlay(proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay", ros_msg: "bosdyn_msgs.msgs.IrMeterOverlay") -> None: - ros_msg.enable = proto.enable - from bosdyn_msgs.msg import IrMeterOverlayNormalizedCoordinates - ros_msg.meter = [] - for _item in proto.meter: - ros_msg.meter.append(IrMeterOverlayNormalizedCoordinates()) - convert_proto_to_bosdyn_msgs_ir_meter_overlay_normalized_coordinates(_item, ros_msg.meter[-1]) - convert_proto_to_bosdyn_msgs_ir_meter_overlay_temp_unit(proto.unit, ros_msg.unit) - ros_msg.unit_is_set = proto.HasField("unit") - from bosdyn_msgs.msg import IrMeterOverlayDeltaPair - ros_msg.delta = [] - for _item in proto.delta: - ros_msg.delta.append(IrMeterOverlayDeltaPair()) - convert_proto_to_bosdyn_msgs_ir_meter_overlay_delta_pair(_item, ros_msg.delta[-1]) - - -def convert_bosdyn_msgs_ir_meter_overlay_to_proto(ros_msg: "bosdyn_msgs.msgs.IrMeterOverlay", proto: "bosdyn.api.spot_cam.compositor_pb2.IrMeterOverlay") -> None: - proto.Clear() - proto.enable = ros_msg.enable - del proto.meter[:] - for _item in ros_msg.meter: - convert_bosdyn_msgs_ir_meter_overlay_normalized_coordinates_to_proto(_item, proto.meter.add()) - if ros_msg.unit_is_set: - convert_bosdyn_msgs_ir_meter_overlay_temp_unit_to_proto(ros_msg.unit, proto.unit) - del proto.delta[:] - for _item in ros_msg.delta: - convert_bosdyn_msgs_ir_meter_overlay_delta_pair_to_proto(_item, proto.delta.add()) - - -def convert_proto_to_bosdyn_msgs_set_ir_meter_overlay_request(proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrMeterOverlayRequest", ros_msg: "bosdyn_msgs.msgs.SetIrMeterOverlayRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ir_meter_overlay(proto.overlay, ros_msg.overlay) - ros_msg.overlay_is_set = proto.HasField("overlay") - - -def convert_bosdyn_msgs_set_ir_meter_overlay_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetIrMeterOverlayRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrMeterOverlayRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.overlay_is_set: - convert_bosdyn_msgs_ir_meter_overlay_to_proto(ros_msg.overlay, proto.overlay) - - -def convert_proto_to_bosdyn_msgs_set_ir_meter_overlay_response(proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrMeterOverlayResponse", ros_msg: "bosdyn_msgs.msgs.SetIrMeterOverlayResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_ir_meter_overlay_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetIrMeterOverlayResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.SetIrMeterOverlayResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ir_meter_overlay_request(proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrMeterOverlayRequest", ros_msg: "bosdyn_msgs.msgs.GetIrMeterOverlayRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_ir_meter_overlay_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetIrMeterOverlayRequest", proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrMeterOverlayRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ir_meter_overlay_response(proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrMeterOverlayResponse", ros_msg: "bosdyn_msgs.msgs.GetIrMeterOverlayResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ir_meter_overlay(proto.overlay, ros_msg.overlay) - ros_msg.overlay_is_set = proto.HasField("overlay") - - -def convert_bosdyn_msgs_get_ir_meter_overlay_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetIrMeterOverlayResponse", proto: "bosdyn.api.spot_cam.compositor_pb2.GetIrMeterOverlayResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.overlay_is_set: - convert_bosdyn_msgs_ir_meter_overlay_to_proto(ros_msg.overlay, proto.overlay) - - -def convert_proto_to_bosdyn_msgs_temperature(proto: "bosdyn.api.spot_cam.health_pb2.Temperature", ros_msg: "bosdyn_msgs.msgs.Temperature") -> None: - ros_msg.channel_name = proto.channel_name - ros_msg.temperature = proto.temperature - - -def convert_bosdyn_msgs_temperature_to_proto(ros_msg: "bosdyn_msgs.msgs.Temperature", proto: "bosdyn.api.spot_cam.health_pb2.Temperature") -> None: - proto.Clear() - proto.channel_name = ros_msg.channel_name - proto.temperature = ros_msg.temperature - - -def convert_proto_to_bosdyn_msgs_clear_bit_events_request(proto: "bosdyn.api.spot_cam.health_pb2.ClearBITEventsRequest", ros_msg: "bosdyn_msgs.msgs.ClearBITEventsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_clear_bit_events_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBITEventsRequest", proto: "bosdyn.api.spot_cam.health_pb2.ClearBITEventsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_clear_bit_events_response(proto: "bosdyn.api.spot_cam.health_pb2.ClearBITEventsResponse", ros_msg: "bosdyn_msgs.msgs.ClearBITEventsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_clear_bit_events_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ClearBITEventsResponse", proto: "bosdyn.api.spot_cam.health_pb2.ClearBITEventsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_bit_status_request(proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetBITStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_bit_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetBITStatusRequest", proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_bit_status_response_degradation_degradation_type(proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse.Degradation.DegradationType", ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponseDegradationDegradationType") -> None: - pass - - -def convert_bosdyn_msgs_get_bit_status_response_degradation_degradation_type_to_proto(ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponseDegradationDegradationType", proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse.Degradation.DegradationType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_get_bit_status_response_degradation(proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse.Degradation", ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponseDegradation") -> None: - ros_msg.type.value = proto.type - ros_msg.description = proto.description - - -def convert_bosdyn_msgs_get_bit_status_response_degradation_to_proto(ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponseDegradation", proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse.Degradation") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.description = ros_msg.description - - -def convert_proto_to_bosdyn_msgs_get_bit_status_response(proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import SystemFault - ros_msg.events = [] - for _item in proto.events: - ros_msg.events.append(SystemFault()) - convert_proto_to_bosdyn_msgs_system_fault(_item, ros_msg.events[-1]) - from bosdyn_msgs.msg import GetBITStatusResponseDegradation - ros_msg.degradations = [] - for _item in proto.degradations: - ros_msg.degradations.append(GetBITStatusResponseDegradation()) - convert_proto_to_bosdyn_msgs_get_bit_status_response_degradation(_item, ros_msg.degradations[-1]) - - -def convert_bosdyn_msgs_get_bit_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetBITStatusResponse", proto: "bosdyn.api.spot_cam.health_pb2.GetBITStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.events[:] - for _item in ros_msg.events: - convert_bosdyn_msgs_system_fault_to_proto(_item, proto.events.add()) - del proto.degradations[:] - for _item in ros_msg.degradations: - convert_bosdyn_msgs_get_bit_status_response_degradation_to_proto(_item, proto.degradations.add()) - - -def convert_proto_to_bosdyn_msgs_get_temperature_request(proto: "bosdyn.api.spot_cam.health_pb2.GetTemperatureRequest", ros_msg: "bosdyn_msgs.msgs.GetTemperatureRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_temperature_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetTemperatureRequest", proto: "bosdyn.api.spot_cam.health_pb2.GetTemperatureRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_temperature_response(proto: "bosdyn.api.spot_cam.health_pb2.GetTemperatureResponse", ros_msg: "bosdyn_msgs.msgs.GetTemperatureResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Temperature - ros_msg.temps = [] - for _item in proto.temps: - ros_msg.temps.append(Temperature()) - convert_proto_to_bosdyn_msgs_temperature(_item, ros_msg.temps[-1]) - - -def convert_bosdyn_msgs_get_temperature_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetTemperatureResponse", proto: "bosdyn.api.spot_cam.health_pb2.GetTemperatureResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.temps[:] - for _item in ros_msg.temps: - convert_bosdyn_msgs_temperature_to_proto(_item, proto.temps.add()) - - -def convert_proto_to_bosdyn_msgs_get_system_log_request(proto: "bosdyn.api.spot_cam.health_pb2.GetSystemLogRequest", ros_msg: "bosdyn_msgs.msgs.GetSystemLogRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_system_log_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSystemLogRequest", proto: "bosdyn.api.spot_cam.health_pb2.GetSystemLogRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_system_log_response(proto: "bosdyn.api.spot_cam.health_pb2.GetSystemLogResponse", ros_msg: "bosdyn_msgs.msgs.GetSystemLogResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_data_chunk(proto.data, ros_msg.data) - ros_msg.data_is_set = proto.HasField("data") - - -def convert_bosdyn_msgs_get_system_log_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSystemLogResponse", proto: "bosdyn.api.spot_cam.health_pb2.GetSystemLogResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.data_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.data, proto.data) - - -def convert_proto_to_bosdyn_msgs_logpoint_record_type(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.RecordType", ros_msg: "bosdyn_msgs.msgs.LogpointRecordType") -> None: - pass - - -def convert_bosdyn_msgs_logpoint_record_type_to_proto(ros_msg: "bosdyn_msgs.msgs.LogpointRecordType", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.RecordType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_logpoint_log_status(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.LogStatus", ros_msg: "bosdyn_msgs.msgs.LogpointLogStatus") -> None: - pass - - -def convert_bosdyn_msgs_logpoint_log_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LogpointLogStatus", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.LogStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_logpoint_queue_status(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.QueueStatus", ros_msg: "bosdyn_msgs.msgs.LogpointQueueStatus") -> None: - pass - - -def convert_bosdyn_msgs_logpoint_queue_status_to_proto(ros_msg: "bosdyn_msgs.msgs.LogpointQueueStatus", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.QueueStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_logpoint_image_params(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.ImageParams", ros_msg: "bosdyn_msgs.msgs.LogpointImageParams") -> None: - ros_msg.width = proto.width - ros_msg.height = proto.height - ros_msg.format.value = proto.format - - -def convert_bosdyn_msgs_logpoint_image_params_to_proto(ros_msg: "bosdyn_msgs.msgs.LogpointImageParams", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.ImageParams") -> None: - proto.Clear() - proto.width = ros_msg.width - proto.height = ros_msg.height - proto.format = ros_msg.format.value - - -def convert_proto_to_bosdyn_msgs_logpoint_calibration(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.Calibration", ros_msg: "bosdyn_msgs.msgs.LogpointCalibration") -> None: - ros_msg.xoffset = proto.xoffset - ros_msg.yoffset = proto.yoffset - ros_msg.width = proto.width - ros_msg.height = proto.height - ros_msg.base_frame_name = proto.base_frame_name - convert_proto_to_geometry_msgs_pose(proto.base_tform_sensor, ros_msg.base_tform_sensor) - ros_msg.base_tform_sensor_is_set = proto.HasField("base_tform_sensor") - convert_proto_to_bosdyn_msgs_camera_pinhole_intrinsics(proto.intrinsics, ros_msg.intrinsics) - ros_msg.intrinsics_is_set = proto.HasField("intrinsics") - - -def convert_bosdyn_msgs_logpoint_calibration_to_proto(ros_msg: "bosdyn_msgs.msgs.LogpointCalibration", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint.Calibration") -> None: - proto.Clear() - proto.xoffset = ros_msg.xoffset - proto.yoffset = ros_msg.yoffset - proto.width = ros_msg.width - proto.height = ros_msg.height - proto.base_frame_name = ros_msg.base_frame_name - if ros_msg.base_tform_sensor_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.base_tform_sensor, proto.base_tform_sensor) - if ros_msg.intrinsics_is_set: - convert_bosdyn_msgs_camera_pinhole_intrinsics_to_proto(ros_msg.intrinsics, proto.intrinsics) - - -def convert_proto_to_bosdyn_msgs_logpoint(proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint", ros_msg: "bosdyn_msgs.msgs.Logpoint") -> None: - ros_msg.name = proto.name - ros_msg.type.value = proto.type - ros_msg.status.value = proto.status - ros_msg.queue_status.value = proto.queue_status - ros_msg.tag = proto.tag - convert_proto_to_builtin_interfaces_time(proto.timestamp, ros_msg.timestamp) - ros_msg.timestamp_is_set = proto.HasField("timestamp") - convert_proto_to_bosdyn_msgs_logpoint_image_params(proto.image_params, ros_msg.image_params) - ros_msg.image_params_is_set = proto.HasField("image_params") - from bosdyn_msgs.msg import LogpointCalibration - ros_msg.calibration = [] - for _item in proto.calibration: - ros_msg.calibration.append(LogpointCalibration()) - convert_proto_to_bosdyn_msgs_logpoint_calibration(_item, ros_msg.calibration[-1]) - - -def convert_bosdyn_msgs_logpoint_to_proto(ros_msg: "bosdyn_msgs.msgs.Logpoint", proto: "bosdyn.api.spot_cam.logging_pb2.Logpoint") -> None: - proto.Clear() - proto.name = ros_msg.name - proto.type = ros_msg.type.value - proto.status = ros_msg.status.value - proto.queue_status = ros_msg.queue_status.value - proto.tag = ros_msg.tag - if ros_msg.timestamp_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp, proto.timestamp) - if ros_msg.image_params_is_set: - convert_bosdyn_msgs_logpoint_image_params_to_proto(ros_msg.image_params, proto.image_params) - del proto.calibration[:] - for _item in ros_msg.calibration: - convert_bosdyn_msgs_logpoint_calibration_to_proto(_item, proto.calibration.add()) - - -def convert_proto_to_bosdyn_msgs_delete_request(proto: "bosdyn.api.spot_cam.logging_pb2.DeleteRequest", ros_msg: "bosdyn_msgs.msgs.DeleteRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - - -def convert_bosdyn_msgs_delete_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteRequest", proto: "bosdyn.api.spot_cam.logging_pb2.DeleteRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.point_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.point, proto.point) - - -def convert_proto_to_bosdyn_msgs_delete_response(proto: "bosdyn.api.spot_cam.logging_pb2.DeleteResponse", ros_msg: "bosdyn_msgs.msgs.DeleteResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_delete_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DeleteResponse", proto: "bosdyn.api.spot_cam.logging_pb2.DeleteResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_retrieve_request(proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRequest", ros_msg: "bosdyn_msgs.msgs.RetrieveRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - - -def convert_bosdyn_msgs_retrieve_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RetrieveRequest", proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.point_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.point, proto.point) - - -def convert_proto_to_bosdyn_msgs_retrieve_response(proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveResponse", ros_msg: "bosdyn_msgs.msgs.RetrieveResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.logpoint, ros_msg.logpoint) - ros_msg.logpoint_is_set = proto.HasField("logpoint") - convert_proto_to_bosdyn_msgs_data_chunk(proto.data, ros_msg.data) - ros_msg.data_is_set = proto.HasField("data") - - -def convert_bosdyn_msgs_retrieve_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RetrieveResponse", proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.logpoint_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.logpoint, proto.logpoint) - if ros_msg.data_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.data, proto.data) - - -def convert_proto_to_bosdyn_msgs_retrieve_raw_data_request(proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRawDataRequest", ros_msg: "bosdyn_msgs.msgs.RetrieveRawDataRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - - -def convert_bosdyn_msgs_retrieve_raw_data_request_to_proto(ros_msg: "bosdyn_msgs.msgs.RetrieveRawDataRequest", proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRawDataRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.point_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.point, proto.point) - - -def convert_proto_to_bosdyn_msgs_retrieve_raw_data_response(proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRawDataResponse", ros_msg: "bosdyn_msgs.msgs.RetrieveRawDataResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.logpoint, ros_msg.logpoint) - ros_msg.logpoint_is_set = proto.HasField("logpoint") - convert_proto_to_bosdyn_msgs_data_chunk(proto.data, ros_msg.data) - ros_msg.data_is_set = proto.HasField("data") - - -def convert_bosdyn_msgs_retrieve_raw_data_response_to_proto(ros_msg: "bosdyn_msgs.msgs.RetrieveRawDataResponse", proto: "bosdyn.api.spot_cam.logging_pb2.RetrieveRawDataResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.logpoint_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.logpoint, proto.logpoint) - if ros_msg.data_is_set: - convert_bosdyn_msgs_data_chunk_to_proto(ros_msg.data, proto.data) - - -def convert_proto_to_bosdyn_msgs_store_request(proto: "bosdyn.api.spot_cam.logging_pb2.StoreRequest", ros_msg: "bosdyn_msgs.msgs.StoreRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_camera(proto.camera, ros_msg.camera) - ros_msg.camera_is_set = proto.HasField("camera") - ros_msg.type.value = proto.type - ros_msg.tag = proto.tag - - -def convert_bosdyn_msgs_store_request_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreRequest", proto: "bosdyn.api.spot_cam.logging_pb2.StoreRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.camera_is_set: - convert_bosdyn_msgs_camera_to_proto(ros_msg.camera, proto.camera) - proto.type = ros_msg.type.value - proto.tag = ros_msg.tag - - -def convert_proto_to_bosdyn_msgs_store_response(proto: "bosdyn.api.spot_cam.logging_pb2.StoreResponse", ros_msg: "bosdyn_msgs.msgs.StoreResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - - -def convert_bosdyn_msgs_store_response_to_proto(ros_msg: "bosdyn_msgs.msgs.StoreResponse", proto: "bosdyn.api.spot_cam.logging_pb2.StoreResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.point_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.point, proto.point) - - -def convert_proto_to_bosdyn_msgs_tag_request(proto: "bosdyn.api.spot_cam.logging_pb2.TagRequest", ros_msg: "bosdyn_msgs.msgs.TagRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_logpoint(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - - -def convert_bosdyn_msgs_tag_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TagRequest", proto: "bosdyn.api.spot_cam.logging_pb2.TagRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.point_is_set: - convert_bosdyn_msgs_logpoint_to_proto(ros_msg.point, proto.point) - - -def convert_proto_to_bosdyn_msgs_tag_response(proto: "bosdyn.api.spot_cam.logging_pb2.TagResponse", ros_msg: "bosdyn_msgs.msgs.TagResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_tag_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TagResponse", proto: "bosdyn.api.spot_cam.logging_pb2.TagResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_cameras_request(proto: "bosdyn.api.spot_cam.logging_pb2.ListCamerasRequest", ros_msg: "bosdyn_msgs.msgs.ListCamerasRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_cameras_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListCamerasRequest", proto: "bosdyn.api.spot_cam.logging_pb2.ListCamerasRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_cameras_response(proto: "bosdyn.api.spot_cam.logging_pb2.ListCamerasResponse", ros_msg: "bosdyn_msgs.msgs.ListCamerasResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Camera - ros_msg.cameras = [] - for _item in proto.cameras: - ros_msg.cameras.append(Camera()) - convert_proto_to_bosdyn_msgs_camera(_item, ros_msg.cameras[-1]) - - -def convert_bosdyn_msgs_list_cameras_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListCamerasResponse", proto: "bosdyn.api.spot_cam.logging_pb2.ListCamerasResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.cameras[:] - for _item in ros_msg.cameras: - convert_bosdyn_msgs_camera_to_proto(_item, proto.cameras.add()) - - -def convert_proto_to_bosdyn_msgs_list_logpoints_request(proto: "bosdyn.api.spot_cam.logging_pb2.ListLogpointsRequest", ros_msg: "bosdyn_msgs.msgs.ListLogpointsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_logpoints_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListLogpointsRequest", proto: "bosdyn.api.spot_cam.logging_pb2.ListLogpointsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_logpoints_response(proto: "bosdyn.api.spot_cam.logging_pb2.ListLogpointsResponse", ros_msg: "bosdyn_msgs.msgs.ListLogpointsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import Logpoint - ros_msg.logpoints = [] - for _item in proto.logpoints: - ros_msg.logpoints.append(Logpoint()) - convert_proto_to_bosdyn_msgs_logpoint(_item, ros_msg.logpoints[-1]) - - -def convert_bosdyn_msgs_list_logpoints_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListLogpointsResponse", proto: "bosdyn.api.spot_cam.logging_pb2.ListLogpointsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.logpoints[:] - for _item in ros_msg.logpoints: - convert_bosdyn_msgs_logpoint_to_proto(_item, proto.logpoints.add()) - - -def convert_proto_to_bosdyn_msgs_set_passphrase_request(proto: "bosdyn.api.spot_cam.logging_pb2.SetPassphraseRequest", ros_msg: "bosdyn_msgs.msgs.SetPassphraseRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.passphrase = proto.passphrase - - -def convert_bosdyn_msgs_set_passphrase_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPassphraseRequest", proto: "bosdyn.api.spot_cam.logging_pb2.SetPassphraseRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.passphrase = ros_msg.passphrase - - -def convert_proto_to_bosdyn_msgs_set_passphrase_response(proto: "bosdyn.api.spot_cam.logging_pb2.SetPassphraseResponse", ros_msg: "bosdyn_msgs.msgs.SetPassphraseResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_passphrase_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPassphraseResponse", proto: "bosdyn.api.spot_cam.logging_pb2.SetPassphraseResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_debug_request(proto: "bosdyn.api.spot_cam.logging_pb2.DebugRequest", ros_msg: "bosdyn_msgs.msgs.DebugRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.enable_temperature = proto.enable_temperature - ros_msg.enable_humidity = proto.enable_humidity - ros_msg.enable_bit = proto.enable_BIT - ros_msg.enable_shock = proto.enable_shock - ros_msg.enable_system_stat = proto.enable_system_stat - - -def convert_bosdyn_msgs_debug_request_to_proto(ros_msg: "bosdyn_msgs.msgs.DebugRequest", proto: "bosdyn.api.spot_cam.logging_pb2.DebugRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.enable_temperature = ros_msg.enable_temperature - proto.enable_humidity = ros_msg.enable_humidity - proto.enable_BIT = ros_msg.enable_bit - proto.enable_shock = ros_msg.enable_shock - proto.enable_system_stat = ros_msg.enable_system_stat - - -def convert_proto_to_bosdyn_msgs_debug_response(proto: "bosdyn.api.spot_cam.logging_pb2.DebugResponse", ros_msg: "bosdyn_msgs.msgs.DebugResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_debug_response_to_proto(ros_msg: "bosdyn_msgs.msgs.DebugResponse", proto: "bosdyn.api.spot_cam.logging_pb2.DebugResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_network_tuple(proto: "bosdyn.api.spot_cam.network_pb2.NetworkTuple", ros_msg: "bosdyn_msgs.msgs.NetworkTuple") -> None: - ros_msg.address = proto.address.value - ros_msg.address_is_set = proto.HasField("address") - ros_msg.netmask = proto.netmask.value - ros_msg.netmask_is_set = proto.HasField("netmask") - ros_msg.gateway = proto.gateway.value - ros_msg.gateway_is_set = proto.HasField("gateway") - ros_msg.mtu = proto.mtu.value - ros_msg.mtu_is_set = proto.HasField("mtu") - - -def convert_bosdyn_msgs_network_tuple_to_proto(ros_msg: "bosdyn_msgs.msgs.NetworkTuple", proto: "bosdyn.api.spot_cam.network_pb2.NetworkTuple") -> None: - proto.Clear() - if ros_msg.address_is_set: - convert_uint32_to_proto(ros_msg.address, proto.address) - if ros_msg.netmask_is_set: - convert_uint32_to_proto(ros_msg.netmask, proto.netmask) - if ros_msg.gateway_is_set: - convert_uint32_to_proto(ros_msg.gateway, proto.gateway) - if ros_msg.mtu_is_set: - convert_uint32_to_proto(ros_msg.mtu, proto.mtu) - - -def convert_proto_to_bosdyn_msgs_get_network_settings_request(proto: "bosdyn.api.spot_cam.network_pb2.GetNetworkSettingsRequest", ros_msg: "bosdyn_msgs.msgs.GetNetworkSettingsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_network_settings_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetNetworkSettingsRequest", proto: "bosdyn.api.spot_cam.network_pb2.GetNetworkSettingsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_network_settings_response(proto: "bosdyn.api.spot_cam.network_pb2.GetNetworkSettingsResponse", ros_msg: "bosdyn_msgs.msgs.GetNetworkSettingsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_network_tuple(proto.settings, ros_msg.settings) - ros_msg.settings_is_set = proto.HasField("settings") - - -def convert_bosdyn_msgs_get_network_settings_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetNetworkSettingsResponse", proto: "bosdyn.api.spot_cam.network_pb2.GetNetworkSettingsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.settings_is_set: - convert_bosdyn_msgs_network_tuple_to_proto(ros_msg.settings, proto.settings) - - -def convert_proto_to_bosdyn_msgs_get_ssl_cert_request(proto: "bosdyn.api.spot_cam.network_pb2.GetSSLCertRequest", ros_msg: "bosdyn_msgs.msgs.GetSSLCertRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_ssl_cert_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSSLCertRequest", proto: "bosdyn.api.spot_cam.network_pb2.GetSSLCertRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ssl_cert_response(proto: "bosdyn.api.spot_cam.network_pb2.GetSSLCertResponse", ros_msg: "bosdyn_msgs.msgs.GetSSLCertResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.certificate = proto.certificate - - -def convert_bosdyn_msgs_get_ssl_cert_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSSLCertResponse", proto: "bosdyn.api.spot_cam.network_pb2.GetSSLCertResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.certificate = ros_msg.certificate - - -def convert_proto_to_bosdyn_msgs_ice_server_servertype(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer", ros_msg: "bosdyn_msgs.msgs.ICEServerServertype") -> None: - pass - - -def convert_bosdyn_msgs_ice_server_servertype_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServerServertype", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ice_server_icetransport(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer", ros_msg: "bosdyn_msgs.msgs.ICEServerIcetransport") -> None: - pass - - -def convert_bosdyn_msgs_ice_server_icetransport_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServerIcetransport", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ice_server_auth_params_oauth_pair(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer.auth_params", ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParamsOauthPair") -> None: - ros_msg.mac_key = proto.MACKey - ros_msg.access_token = proto.AccessToken - - -def convert_bosdyn_msgs_ice_server_auth_params_oauth_pair_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParamsOauthPair", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer.auth_params") -> None: - proto.Clear() - proto.MACKey = ros_msg.mac_key - proto.AccessToken = ros_msg.access_token - - -def convert_proto_to_bosdyn_msgs_ice_server_auth_params_one_of_credential(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer.auth_params", ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParamsOneOfCredential") -> None: - if proto.HasField("oauth"): - ros_msg.credential_choice = ros_msg.CREDENTIAL_OAUTH_SET - convert_proto_to_bosdyn_msgs_ice_server_auth_params_oauth_pair(proto.oauth, ros_msg.oauth) - if proto.HasField("password"): - ros_msg.credential_choice = ros_msg.CREDENTIAL_PASSWORD_SET - ros_msg.password = proto.password.value - - -def convert_bosdyn_msgs_ice_server_auth_params_one_of_credential_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParamsOneOfCredential", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer.auth_params") -> None: - proto.ClearField("credential") - if ros_msg.credential_choice == ros_msg.CREDENTIAL_OAUTH_SET: - convert_bosdyn_msgs_ice_server_auth_params_oauth_pair_to_proto(ros_msg.oauth, proto.oauth) - if ros_msg.credential_choice == ros_msg.CREDENTIAL_PASSWORD_SET: - convert_string_to_proto(ros_msg.password, proto.password) - - -def convert_proto_to_bosdyn_msgs_ice_server_auth_params(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer", ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParams") -> None: - ros_msg.username = proto.username.value - ros_msg.username_is_set = proto.HasField("username") - convert_proto_to_bosdyn_msgs_ice_server_auth_params_one_of_credential(proto, ros_msg.credential) - - -def convert_bosdyn_msgs_ice_server_auth_params_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServerAuthParams", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer") -> None: - proto.Clear() - if ros_msg.username_is_set: - convert_string_to_proto(ros_msg.username, proto.username) - convert_bosdyn_msgs_ice_server_auth_params_one_of_credential_to_proto(ros_msg.credential, proto) - - -def convert_proto_to_bosdyn_msgs_ice_server(proto: "bosdyn.api.spot_cam.network_pb2.ICEServer", ros_msg: "bosdyn_msgs.msgs.ICEServer") -> None: - ros_msg.type.value = proto.type - ros_msg.address = proto.address - ros_msg.port = proto.port - ros_msg.transport.value = proto.transport - convert_proto_to_bosdyn_msgs_ice_server_auth_params(proto.auth, ros_msg.auth) - ros_msg.auth_is_set = proto.HasField("auth") - - -def convert_bosdyn_msgs_ice_server_to_proto(ros_msg: "bosdyn_msgs.msgs.ICEServer", proto: "bosdyn.api.spot_cam.network_pb2.ICEServer") -> None: - proto.Clear() - proto.type = ros_msg.type.value - proto.address = ros_msg.address - proto.port = ros_msg.port - proto.transport = ros_msg.transport.value - if ros_msg.auth_is_set: - convert_bosdyn_msgs_ice_server_auth_params_to_proto(ros_msg.auth, proto.auth) - - -def convert_proto_to_bosdyn_msgs_get_ice_configuration_request(proto: "bosdyn.api.spot_cam.network_pb2.GetICEConfigurationRequest", ros_msg: "bosdyn_msgs.msgs.GetICEConfigurationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_ice_configuration_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetICEConfigurationRequest", proto: "bosdyn.api.spot_cam.network_pb2.GetICEConfigurationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ice_configuration_response(proto: "bosdyn.api.spot_cam.network_pb2.GetICEConfigurationResponse", ros_msg: "bosdyn_msgs.msgs.GetICEConfigurationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ICEServer - ros_msg.servers = [] - for _item in proto.servers: - ros_msg.servers.append(ICEServer()) - convert_proto_to_bosdyn_msgs_ice_server(_item, ros_msg.servers[-1]) - - -def convert_bosdyn_msgs_get_ice_configuration_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetICEConfigurationResponse", proto: "bosdyn.api.spot_cam.network_pb2.GetICEConfigurationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.servers[:] - for _item in ros_msg.servers: - convert_bosdyn_msgs_ice_server_to_proto(_item, proto.servers.add()) - - -def convert_proto_to_bosdyn_msgs_set_ice_configuration_request(proto: "bosdyn.api.spot_cam.network_pb2.SetICEConfigurationRequest", ros_msg: "bosdyn_msgs.msgs.SetICEConfigurationRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import ICEServer - ros_msg.servers = [] - for _item in proto.servers: - ros_msg.servers.append(ICEServer()) - convert_proto_to_bosdyn_msgs_ice_server(_item, ros_msg.servers[-1]) - - -def convert_bosdyn_msgs_set_ice_configuration_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetICEConfigurationRequest", proto: "bosdyn.api.spot_cam.network_pb2.SetICEConfigurationRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.servers[:] - for _item in ros_msg.servers: - convert_bosdyn_msgs_ice_server_to_proto(_item, proto.servers.add()) - - -def convert_proto_to_bosdyn_msgs_set_ice_configuration_response(proto: "bosdyn.api.spot_cam.network_pb2.SetICEConfigurationResponse", ros_msg: "bosdyn_msgs.msgs.SetICEConfigurationResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_ice_configuration_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetICEConfigurationResponse", proto: "bosdyn.api.spot_cam.network_pb2.SetICEConfigurationResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_power_status(proto: "bosdyn.api.spot_cam.power_pb2.PowerStatus", ros_msg: "bosdyn_msgs.msgs.PowerStatus") -> None: - ros_msg.ptz = proto.ptz.value - ros_msg.ptz_is_set = proto.HasField("ptz") - ros_msg.aux1 = proto.aux1.value - ros_msg.aux1_is_set = proto.HasField("aux1") - ros_msg.aux2 = proto.aux2.value - ros_msg.aux2_is_set = proto.HasField("aux2") - ros_msg.external_mic = proto.external_mic.value - ros_msg.external_mic_is_set = proto.HasField("external_mic") - - -def convert_bosdyn_msgs_power_status_to_proto(ros_msg: "bosdyn_msgs.msgs.PowerStatus", proto: "bosdyn.api.spot_cam.power_pb2.PowerStatus") -> None: - proto.Clear() - if ros_msg.ptz_is_set: - convert_bool_to_proto(ros_msg.ptz, proto.ptz) - if ros_msg.aux1_is_set: - convert_bool_to_proto(ros_msg.aux1, proto.aux1) - if ros_msg.aux2_is_set: - convert_bool_to_proto(ros_msg.aux2, proto.aux2) - if ros_msg.external_mic_is_set: - convert_bool_to_proto(ros_msg.external_mic, proto.external_mic) - - -def convert_proto_to_bosdyn_msgs_get_power_status_request(proto: "bosdyn.api.spot_cam.power_pb2.GetPowerStatusRequest", ros_msg: "bosdyn_msgs.msgs.GetPowerStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_power_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPowerStatusRequest", proto: "bosdyn.api.spot_cam.power_pb2.GetPowerStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_power_status_response(proto: "bosdyn.api.spot_cam.power_pb2.GetPowerStatusResponse", ros_msg: "bosdyn_msgs.msgs.GetPowerStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_power_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_get_power_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPowerStatusResponse", proto: "bosdyn.api.spot_cam.power_pb2.GetPowerStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_power_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_set_power_status_request(proto: "bosdyn.api.spot_cam.power_pb2.SetPowerStatusRequest", ros_msg: "bosdyn_msgs.msgs.SetPowerStatusRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_power_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_set_power_status_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPowerStatusRequest", proto: "bosdyn.api.spot_cam.power_pb2.SetPowerStatusRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_power_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_set_power_status_response(proto: "bosdyn.api.spot_cam.power_pb2.SetPowerStatusResponse", ros_msg: "bosdyn_msgs.msgs.SetPowerStatusResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_power_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_set_power_status_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPowerStatusResponse", proto: "bosdyn.api.spot_cam.power_pb2.SetPowerStatusResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_power_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_cycle_power_request(proto: "bosdyn.api.spot_cam.power_pb2.CyclePowerRequest", ros_msg: "bosdyn_msgs.msgs.CyclePowerRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_power_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_cycle_power_request_to_proto(ros_msg: "bosdyn_msgs.msgs.CyclePowerRequest", proto: "bosdyn.api.spot_cam.power_pb2.CyclePowerRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_power_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_cycle_power_response(proto: "bosdyn.api.spot_cam.power_pb2.CyclePowerResponse", ros_msg: "bosdyn_msgs.msgs.CyclePowerResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_power_status(proto.status, ros_msg.status) - ros_msg.status_is_set = proto.HasField("status") - - -def convert_bosdyn_msgs_cycle_power_response_to_proto(ros_msg: "bosdyn_msgs.msgs.CyclePowerResponse", proto: "bosdyn.api.spot_cam.power_pb2.CyclePowerResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.status_is_set: - convert_bosdyn_msgs_power_status_to_proto(ros_msg.status, proto.status) - - -def convert_proto_to_bosdyn_msgs_ptz_description_limits(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzDescription.Limits", ros_msg: "bosdyn_msgs.msgs.PtzDescriptionLimits") -> None: - ros_msg.min = proto.min.value - ros_msg.min_is_set = proto.HasField("min") - ros_msg.max = proto.max.value - ros_msg.max_is_set = proto.HasField("max") - - -def convert_bosdyn_msgs_ptz_description_limits_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzDescriptionLimits", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzDescription.Limits") -> None: - proto.Clear() - if ros_msg.min_is_set: - convert_float32_to_proto(ros_msg.min, proto.min) - if ros_msg.max_is_set: - convert_float32_to_proto(ros_msg.max, proto.max) - - -def convert_proto_to_bosdyn_msgs_ptz_description(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzDescription", ros_msg: "bosdyn_msgs.msgs.PtzDescription") -> None: - ros_msg.name = proto.name - convert_proto_to_bosdyn_msgs_ptz_description_limits(proto.pan_limit, ros_msg.pan_limit) - ros_msg.pan_limit_is_set = proto.HasField("pan_limit") - convert_proto_to_bosdyn_msgs_ptz_description_limits(proto.tilt_limit, ros_msg.tilt_limit) - ros_msg.tilt_limit_is_set = proto.HasField("tilt_limit") - convert_proto_to_bosdyn_msgs_ptz_description_limits(proto.zoom_limit, ros_msg.zoom_limit) - ros_msg.zoom_limit_is_set = proto.HasField("zoom_limit") - - -def convert_bosdyn_msgs_ptz_description_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzDescription", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzDescription") -> None: - proto.Clear() - proto.name = ros_msg.name - if ros_msg.pan_limit_is_set: - convert_bosdyn_msgs_ptz_description_limits_to_proto(ros_msg.pan_limit, proto.pan_limit) - if ros_msg.tilt_limit_is_set: - convert_bosdyn_msgs_ptz_description_limits_to_proto(ros_msg.tilt_limit, proto.tilt_limit) - if ros_msg.zoom_limit_is_set: - convert_bosdyn_msgs_ptz_description_limits_to_proto(ros_msg.zoom_limit, proto.zoom_limit) - - -def convert_proto_to_bosdyn_msgs_ptz_position(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzPosition", ros_msg: "bosdyn_msgs.msgs.PtzPosition") -> None: - convert_proto_to_bosdyn_msgs_ptz_description(proto.ptz, ros_msg.ptz) - ros_msg.ptz_is_set = proto.HasField("ptz") - ros_msg.pan = proto.pan.value - ros_msg.pan_is_set = proto.HasField("pan") - ros_msg.tilt = proto.tilt.value - ros_msg.tilt_is_set = proto.HasField("tilt") - ros_msg.zoom = proto.zoom.value - ros_msg.zoom_is_set = proto.HasField("zoom") - - -def convert_bosdyn_msgs_ptz_position_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzPosition", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzPosition") -> None: - proto.Clear() - if ros_msg.ptz_is_set: - convert_bosdyn_msgs_ptz_description_to_proto(ros_msg.ptz, proto.ptz) - if ros_msg.pan_is_set: - convert_float32_to_proto(ros_msg.pan, proto.pan) - if ros_msg.tilt_is_set: - convert_float32_to_proto(ros_msg.tilt, proto.tilt) - if ros_msg.zoom_is_set: - convert_float32_to_proto(ros_msg.zoom, proto.zoom) - - -def convert_proto_to_bosdyn_msgs_ptz_velocity(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzVelocity", ros_msg: "bosdyn_msgs.msgs.PtzVelocity") -> None: - convert_proto_to_bosdyn_msgs_ptz_description(proto.ptz, ros_msg.ptz) - ros_msg.ptz_is_set = proto.HasField("ptz") - ros_msg.pan = proto.pan.value - ros_msg.pan_is_set = proto.HasField("pan") - ros_msg.tilt = proto.tilt.value - ros_msg.tilt_is_set = proto.HasField("tilt") - ros_msg.zoom = proto.zoom.value - ros_msg.zoom_is_set = proto.HasField("zoom") - - -def convert_bosdyn_msgs_ptz_velocity_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzVelocity", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzVelocity") -> None: - proto.Clear() - if ros_msg.ptz_is_set: - convert_bosdyn_msgs_ptz_description_to_proto(ros_msg.ptz, proto.ptz) - if ros_msg.pan_is_set: - convert_float32_to_proto(ros_msg.pan, proto.pan) - if ros_msg.tilt_is_set: - convert_float32_to_proto(ros_msg.tilt, proto.tilt) - if ros_msg.zoom_is_set: - convert_float32_to_proto(ros_msg.zoom, proto.zoom) - - -def convert_proto_to_bosdyn_msgs_get_ptz_position_request(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzPositionRequest", ros_msg: "bosdyn_msgs.msgs.GetPtzPositionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_description(proto.ptz, ros_msg.ptz) - ros_msg.ptz_is_set = proto.HasField("ptz") - - -def convert_bosdyn_msgs_get_ptz_position_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzPositionRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzPositionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.ptz_is_set: - convert_bosdyn_msgs_ptz_description_to_proto(ros_msg.ptz, proto.ptz) - - -def convert_proto_to_bosdyn_msgs_get_ptz_position_response(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzPositionResponse", ros_msg: "bosdyn_msgs.msgs.GetPtzPositionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_position(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - - -def convert_bosdyn_msgs_get_ptz_position_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzPositionResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzPositionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.position_is_set: - convert_bosdyn_msgs_ptz_position_to_proto(ros_msg.position, proto.position) - - -def convert_proto_to_bosdyn_msgs_get_ptz_velocity_request(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzVelocityRequest", ros_msg: "bosdyn_msgs.msgs.GetPtzVelocityRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_description(proto.ptz, ros_msg.ptz) - ros_msg.ptz_is_set = proto.HasField("ptz") - - -def convert_bosdyn_msgs_get_ptz_velocity_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzVelocityRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzVelocityRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.ptz_is_set: - convert_bosdyn_msgs_ptz_description_to_proto(ros_msg.ptz, proto.ptz) - - -def convert_proto_to_bosdyn_msgs_get_ptz_velocity_response(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzVelocityResponse", ros_msg: "bosdyn_msgs.msgs.GetPtzVelocityResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_velocity(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - - -def convert_bosdyn_msgs_get_ptz_velocity_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzVelocityResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzVelocityResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.velocity_is_set: - convert_bosdyn_msgs_ptz_velocity_to_proto(ros_msg.velocity, proto.velocity) - - -def convert_proto_to_bosdyn_msgs_list_ptz_request(proto: "bosdyn.api.spot_cam.ptz_pb2.ListPtzRequest", ros_msg: "bosdyn_msgs.msgs.ListPtzRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_list_ptz_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPtzRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.ListPtzRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_list_ptz_response(proto: "bosdyn.api.spot_cam.ptz_pb2.ListPtzResponse", ros_msg: "bosdyn_msgs.msgs.ListPtzResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import PtzDescription - ros_msg.ptzs = [] - for _item in proto.ptzs: - ros_msg.ptzs.append(PtzDescription()) - convert_proto_to_bosdyn_msgs_ptz_description(_item, ros_msg.ptzs[-1]) - - -def convert_bosdyn_msgs_list_ptz_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListPtzResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.ListPtzResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.ptzs[:] - for _item in ros_msg.ptzs: - convert_bosdyn_msgs_ptz_description_to_proto(_item, proto.ptzs.add()) - - -def convert_proto_to_bosdyn_msgs_set_ptz_position_request(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzPositionRequest", ros_msg: "bosdyn_msgs.msgs.SetPtzPositionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_position(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - - -def convert_bosdyn_msgs_set_ptz_position_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzPositionRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzPositionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.position_is_set: - convert_bosdyn_msgs_ptz_position_to_proto(ros_msg.position, proto.position) - - -def convert_proto_to_bosdyn_msgs_set_ptz_position_response(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzPositionResponse", ros_msg: "bosdyn_msgs.msgs.SetPtzPositionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_position(proto.position, ros_msg.position) - ros_msg.position_is_set = proto.HasField("position") - - -def convert_bosdyn_msgs_set_ptz_position_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzPositionResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzPositionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.position_is_set: - convert_bosdyn_msgs_ptz_position_to_proto(ros_msg.position, proto.position) - - -def convert_proto_to_bosdyn_msgs_set_ptz_velocity_request(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzVelocityRequest", ros_msg: "bosdyn_msgs.msgs.SetPtzVelocityRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_velocity(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - - -def convert_bosdyn_msgs_set_ptz_velocity_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzVelocityRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzVelocityRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.velocity_is_set: - convert_bosdyn_msgs_ptz_velocity_to_proto(ros_msg.velocity, proto.velocity) - - -def convert_proto_to_bosdyn_msgs_set_ptz_velocity_response(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzVelocityResponse", ros_msg: "bosdyn_msgs.msgs.SetPtzVelocityResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_velocity(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - - -def convert_bosdyn_msgs_set_ptz_velocity_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzVelocityResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzVelocityResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.velocity_is_set: - convert_bosdyn_msgs_ptz_velocity_to_proto(ros_msg.velocity, proto.velocity) - - -def convert_proto_to_bosdyn_msgs_initialize_lens_request(proto: "bosdyn.api.spot_cam.ptz_pb2.InitializeLensRequest", ros_msg: "bosdyn_msgs.msgs.InitializeLensRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_initialize_lens_request_to_proto(ros_msg: "bosdyn_msgs.msgs.InitializeLensRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.InitializeLensRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_initialize_lens_response(proto: "bosdyn.api.spot_cam.ptz_pb2.InitializeLensResponse", ros_msg: "bosdyn_msgs.msgs.InitializeLensResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_initialize_lens_response_to_proto(ros_msg: "bosdyn_msgs.msgs.InitializeLensResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.InitializeLensResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_ptz_focus_state_ptz_focus_mode(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzFocusState.PtzFocusMode", ros_msg: "bosdyn_msgs.msgs.PtzFocusStatePtzFocusMode") -> None: - pass - - -def convert_bosdyn_msgs_ptz_focus_state_ptz_focus_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzFocusStatePtzFocusMode", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzFocusState.PtzFocusMode") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_ptz_focus_state(proto: "bosdyn.api.spot_cam.ptz_pb2.PtzFocusState", ros_msg: "bosdyn_msgs.msgs.PtzFocusState") -> None: - ros_msg.mode.value = proto.mode - ros_msg.focus_position = proto.focus_position.value - ros_msg.focus_position_is_set = proto.HasField("focus_position") - ros_msg.approx_distance = proto.approx_distance.value - ros_msg.approx_distance_is_set = proto.HasField("approx_distance") - - -def convert_bosdyn_msgs_ptz_focus_state_to_proto(ros_msg: "bosdyn_msgs.msgs.PtzFocusState", proto: "bosdyn.api.spot_cam.ptz_pb2.PtzFocusState") -> None: - proto.Clear() - proto.mode = ros_msg.mode.value - if ros_msg.focus_position_is_set: - convert_int32_to_proto(ros_msg.focus_position, proto.focus_position) - if ros_msg.approx_distance_is_set: - convert_float32_to_proto(ros_msg.approx_distance, proto.approx_distance) - - -def convert_proto_to_bosdyn_msgs_set_ptz_focus_state_request(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzFocusStateRequest", ros_msg: "bosdyn_msgs.msgs.SetPtzFocusStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_focus_state(proto.focus_state, ros_msg.focus_state) - ros_msg.focus_state_is_set = proto.HasField("focus_state") - - -def convert_bosdyn_msgs_set_ptz_focus_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzFocusStateRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzFocusStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.focus_state_is_set: - convert_bosdyn_msgs_ptz_focus_state_to_proto(ros_msg.focus_state, proto.focus_state) - - -def convert_proto_to_bosdyn_msgs_set_ptz_focus_state_response(proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzFocusStateResponse", ros_msg: "bosdyn_msgs.msgs.SetPtzFocusStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_set_ptz_focus_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetPtzFocusStateResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.SetPtzFocusStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ptz_focus_state_request(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzFocusStateRequest", ros_msg: "bosdyn_msgs.msgs.GetPtzFocusStateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_ptz_focus_state_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzFocusStateRequest", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzFocusStateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_ptz_focus_state_response(proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzFocusStateResponse", ros_msg: "bosdyn_msgs.msgs.GetPtzFocusStateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_ptz_focus_state(proto.focus_state, ros_msg.focus_state) - ros_msg.focus_state_is_set = proto.HasField("focus_state") - - -def convert_bosdyn_msgs_get_ptz_focus_state_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetPtzFocusStateResponse", proto: "bosdyn.api.spot_cam.ptz_pb2.GetPtzFocusStateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.focus_state_is_set: - convert_bosdyn_msgs_ptz_focus_state_to_proto(ros_msg.focus_state, proto.focus_state) - - -def convert_proto_to_bosdyn_msgs_stream_params_awb_mode_enum(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AwbModeEnum", ros_msg: "bosdyn_msgs.msgs.StreamParamsAwbModeEnum") -> None: - pass - - -def convert_bosdyn_msgs_stream_params_awb_mode_enum_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsAwbModeEnum", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AwbModeEnum") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_stream_params_awb_mode(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AwbMode", ros_msg: "bosdyn_msgs.msgs.StreamParamsAwbMode") -> None: - ros_msg.awb.value = proto.awb - - -def convert_bosdyn_msgs_stream_params_awb_mode_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsAwbMode", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AwbMode") -> None: - proto.Clear() - proto.awb = ros_msg.awb.value - - -def convert_proto_to_bosdyn_msgs_stream_params_auto_exposure(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AutoExposure", ros_msg: "bosdyn_msgs.msgs.StreamParamsAutoExposure") -> None: - pass - - -def convert_bosdyn_msgs_stream_params_auto_exposure_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsAutoExposure", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.AutoExposure") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_stream_params_sync_auto_exposure(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.SyncAutoExposure", ros_msg: "bosdyn_msgs.msgs.StreamParamsSyncAutoExposure") -> None: - ros_msg.brightness_target = proto.brightness_target.value - ros_msg.brightness_target_is_set = proto.HasField("brightness_target") - - -def convert_bosdyn_msgs_stream_params_sync_auto_exposure_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsSyncAutoExposure", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.SyncAutoExposure") -> None: - proto.Clear() - if ros_msg.brightness_target_is_set: - convert_int32_to_proto(ros_msg.brightness_target, proto.brightness_target) - - -def convert_proto_to_bosdyn_msgs_stream_params_manual_exposure(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.ManualExposure", ros_msg: "bosdyn_msgs.msgs.StreamParamsManualExposure") -> None: - convert_proto_to_builtin_interfaces_duration(proto.exposure, ros_msg.exposure) - ros_msg.exposure_is_set = proto.HasField("exposure") - ros_msg.gain = proto.gain.value - ros_msg.gain_is_set = proto.HasField("gain") - - -def convert_bosdyn_msgs_stream_params_manual_exposure_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsManualExposure", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams.ManualExposure") -> None: - proto.Clear() - if ros_msg.exposure_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.exposure, proto.exposure) - if ros_msg.gain_is_set: - convert_float32_to_proto(ros_msg.gain, proto.gain) - - -def convert_proto_to_bosdyn_msgs_stream_params_one_of_exposure(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams", ros_msg: "bosdyn_msgs.msgs.StreamParamsOneOfExposure") -> None: - if proto.HasField("auto_exposure"): - ros_msg.exposure_choice = ros_msg.EXPOSURE_AUTO_EXPOSURE_SET - convert_proto_to_bosdyn_msgs_stream_params_auto_exposure(proto.auto_exposure, ros_msg.auto_exposure) - if proto.HasField("sync_exposure"): - ros_msg.exposure_choice = ros_msg.EXPOSURE_SYNC_EXPOSURE_SET - convert_proto_to_bosdyn_msgs_stream_params_sync_auto_exposure(proto.sync_exposure, ros_msg.sync_exposure) - if proto.HasField("manual_exposure"): - ros_msg.exposure_choice = ros_msg.EXPOSURE_MANUAL_EXPOSURE_SET - convert_proto_to_bosdyn_msgs_stream_params_manual_exposure(proto.manual_exposure, ros_msg.manual_exposure) - - -def convert_bosdyn_msgs_stream_params_one_of_exposure_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParamsOneOfExposure", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams") -> None: - proto.ClearField("exposure") - if ros_msg.exposure_choice == ros_msg.EXPOSURE_AUTO_EXPOSURE_SET: - convert_bosdyn_msgs_stream_params_auto_exposure_to_proto(ros_msg.auto_exposure, proto.auto_exposure) - if ros_msg.exposure_choice == ros_msg.EXPOSURE_SYNC_EXPOSURE_SET: - convert_bosdyn_msgs_stream_params_sync_auto_exposure_to_proto(ros_msg.sync_exposure, proto.sync_exposure) - if ros_msg.exposure_choice == ros_msg.EXPOSURE_MANUAL_EXPOSURE_SET: - convert_bosdyn_msgs_stream_params_manual_exposure_to_proto(ros_msg.manual_exposure, proto.manual_exposure) - - -def convert_proto_to_bosdyn_msgs_stream_params(proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams", ros_msg: "bosdyn_msgs.msgs.StreamParams") -> None: - ros_msg.targetbitrate = proto.targetbitrate.value - ros_msg.targetbitrate_is_set = proto.HasField("targetbitrate") - ros_msg.refreshinterval = proto.refreshinterval.value - ros_msg.refreshinterval_is_set = proto.HasField("refreshinterval") - ros_msg.idrinterval = proto.idrinterval.value - ros_msg.idrinterval_is_set = proto.HasField("idrinterval") - convert_proto_to_bosdyn_msgs_stream_params_awb_mode(proto.awb, ros_msg.awb) - ros_msg.awb_is_set = proto.HasField("awb") - convert_proto_to_bosdyn_msgs_stream_params_one_of_exposure(proto, ros_msg.exposure) - - -def convert_bosdyn_msgs_stream_params_to_proto(ros_msg: "bosdyn_msgs.msgs.StreamParams", proto: "bosdyn.api.spot_cam.streamquality_pb2.StreamParams") -> None: - proto.Clear() - if ros_msg.targetbitrate_is_set: - convert_int64_to_proto(ros_msg.targetbitrate, proto.targetbitrate) - if ros_msg.refreshinterval_is_set: - convert_int64_to_proto(ros_msg.refreshinterval, proto.refreshinterval) - if ros_msg.idrinterval_is_set: - convert_int64_to_proto(ros_msg.idrinterval, proto.idrinterval) - if ros_msg.awb_is_set: - convert_bosdyn_msgs_stream_params_awb_mode_to_proto(ros_msg.awb, proto.awb) - convert_bosdyn_msgs_stream_params_one_of_exposure_to_proto(ros_msg.exposure, proto) - - -def convert_proto_to_bosdyn_msgs_get_stream_params_request(proto: "bosdyn.api.spot_cam.streamquality_pb2.GetStreamParamsRequest", ros_msg: "bosdyn_msgs.msgs.GetStreamParamsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_stream_params_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStreamParamsRequest", proto: "bosdyn.api.spot_cam.streamquality_pb2.GetStreamParamsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_stream_params_response(proto: "bosdyn.api.spot_cam.streamquality_pb2.GetStreamParamsResponse", ros_msg: "bosdyn_msgs.msgs.GetStreamParamsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_stream_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_get_stream_params_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetStreamParamsResponse", proto: "bosdyn.api.spot_cam.streamquality_pb2.GetStreamParamsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_stream_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_set_stream_params_request(proto: "bosdyn.api.spot_cam.streamquality_pb2.SetStreamParamsRequest", ros_msg: "bosdyn_msgs.msgs.SetStreamParamsRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_stream_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_set_stream_params_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SetStreamParamsRequest", proto: "bosdyn.api.spot_cam.streamquality_pb2.SetStreamParamsRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_stream_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_set_stream_params_response(proto: "bosdyn.api.spot_cam.streamquality_pb2.SetStreamParamsResponse", ros_msg: "bosdyn_msgs.msgs.SetStreamParamsResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_stream_params(proto.params, ros_msg.params) - ros_msg.params_is_set = proto.HasField("params") - - -def convert_bosdyn_msgs_set_stream_params_response_to_proto(ros_msg: "bosdyn_msgs.msgs.SetStreamParamsResponse", proto: "bosdyn.api.spot_cam.streamquality_pb2.SetStreamParamsResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.params_is_set: - convert_bosdyn_msgs_stream_params_to_proto(ros_msg.params, proto.params) - - -def convert_proto_to_bosdyn_msgs_enable_congestion_control_request(proto: "bosdyn.api.spot_cam.streamquality_pb2.EnableCongestionControlRequest", ros_msg: "bosdyn_msgs.msgs.EnableCongestionControlRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.enable_congestion_control = proto.enable_congestion_control - - -def convert_bosdyn_msgs_enable_congestion_control_request_to_proto(ros_msg: "bosdyn_msgs.msgs.EnableCongestionControlRequest", proto: "bosdyn.api.spot_cam.streamquality_pb2.EnableCongestionControlRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - proto.enable_congestion_control = ros_msg.enable_congestion_control - - -def convert_proto_to_bosdyn_msgs_enable_congestion_control_response(proto: "bosdyn.api.spot_cam.streamquality_pb2.EnableCongestionControlResponse", ros_msg: "bosdyn_msgs.msgs.EnableCongestionControlResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_enable_congestion_control_response_to_proto(ros_msg: "bosdyn_msgs.msgs.EnableCongestionControlResponse", proto: "bosdyn.api.spot_cam.streamquality_pb2.EnableCongestionControlResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_software_version_request(proto: "bosdyn.api.spot_cam.version_pb2.GetSoftwareVersionRequest", ros_msg: "bosdyn_msgs.msgs.GetSoftwareVersionRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - - -def convert_bosdyn_msgs_get_software_version_request_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSoftwareVersionRequest", proto: "bosdyn.api.spot_cam.version_pb2.GetSoftwareVersionRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - - -def convert_proto_to_bosdyn_msgs_get_software_version_response(proto: "bosdyn.api.spot_cam.version_pb2.GetSoftwareVersionResponse", ros_msg: "bosdyn_msgs.msgs.GetSoftwareVersionResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_software_version(proto.version, ros_msg.version) - ros_msg.version_is_set = proto.HasField("version") - ros_msg.detail = proto.detail - - -def convert_bosdyn_msgs_get_software_version_response_to_proto(ros_msg: "bosdyn_msgs.msgs.GetSoftwareVersionResponse", proto: "bosdyn.api.spot_cam.version_pb2.GetSoftwareVersionResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.version_is_set: - convert_bosdyn_msgs_software_version_to_proto(ros_msg.version, proto.version) - proto.detail = ros_msg.detail - - -def convert_proto_to_bosdyn_msgs_stair_transform(proto: "bosdyn.api.stairs_pb2.StairTransform", ros_msg: "bosdyn_msgs.msgs.StairTransform") -> None: - convert_proto_to_geometry_msgs_pose(proto.frame_tform_stairs, ros_msg.frame_tform_stairs) - ros_msg.frame_tform_stairs_is_set = proto.HasField("frame_tform_stairs") - ros_msg.frame_name = proto.frame_name - - -def convert_bosdyn_msgs_stair_transform_to_proto(ros_msg: "bosdyn_msgs.msgs.StairTransform", proto: "bosdyn.api.stairs_pb2.StairTransform") -> None: - proto.Clear() - if ros_msg.frame_tform_stairs_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.frame_tform_stairs, proto.frame_tform_stairs) - proto.frame_name = ros_msg.frame_name - - -def convert_proto_to_bosdyn_msgs_staircase_knowledge_type(proto: "bosdyn.api.stairs_pb2.Staircase.KnowledgeType", ros_msg: "bosdyn_msgs.msgs.StaircaseKnowledgeType") -> None: - pass - - -def convert_bosdyn_msgs_staircase_knowledge_type_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseKnowledgeType", proto: "bosdyn.api.stairs_pb2.Staircase.KnowledgeType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_staircase_width_bounded_width(proto: "bosdyn.api.stairs_pb2.Staircase.Width.BoundedWidth", ros_msg: "bosdyn_msgs.msgs.StaircaseWidthBoundedWidth") -> None: - pass - - -def convert_bosdyn_msgs_staircase_width_bounded_width_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseWidthBoundedWidth", proto: "bosdyn.api.stairs_pb2.Staircase.Width.BoundedWidth") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_staircase_width(proto: "bosdyn.api.stairs_pb2.Staircase.Width", ros_msg: "bosdyn_msgs.msgs.StaircaseWidth") -> None: - ros_msg.width = proto.width - ros_msg.bounded_width.value = proto.bounded_width - - -def convert_bosdyn_msgs_staircase_width_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseWidth", proto: "bosdyn.api.stairs_pb2.Staircase.Width") -> None: - proto.Clear() - proto.width = ros_msg.width - proto.bounded_width = ros_msg.bounded_width.value - - -def convert_proto_to_bosdyn_msgs_staircase_step(proto: "bosdyn.api.stairs_pb2.Staircase.Step", ros_msg: "bosdyn_msgs.msgs.StaircaseStep") -> None: - convert_proto_to_geometry_msgs_vector3(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - convert_proto_to_bosdyn_msgs_vec2(proto.north, ros_msg.north) - ros_msg.north_is_set = proto.HasField("north") - convert_proto_to_bosdyn_msgs_staircase_width(proto.width, ros_msg.width) - ros_msg.width_is_set = proto.HasField("width") - - -def convert_bosdyn_msgs_staircase_step_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseStep", proto: "bosdyn.api.stairs_pb2.Staircase.Step") -> None: - proto.Clear() - if ros_msg.point_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.point, proto.point) - if ros_msg.north_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.north, proto.north) - if ros_msg.width_is_set: - convert_bosdyn_msgs_staircase_width_to_proto(ros_msg.width, proto.width) - - -def convert_proto_to_bosdyn_msgs_staircase(proto: "bosdyn.api.stairs_pb2.Staircase", ros_msg: "bosdyn_msgs.msgs.Staircase") -> None: - ros_msg.knowledge_type.value = proto.knowledge_type - convert_proto_to_bosdyn_msgs_stair_transform(proto.stair_tform, ros_msg.stair_tform) - ros_msg.stair_tform_is_set = proto.HasField("stair_tform") - ros_msg.number_of_steps = proto.number_of_steps - ros_msg.average_rise = proto.average_rise - ros_msg.average_run = proto.average_run - convert_proto_to_bosdyn_msgs_staircase_width(proto.average_width, ros_msg.average_width) - ros_msg.average_width_is_set = proto.HasField("average_width") - from bosdyn_msgs.msg import StaircaseStep - ros_msg.steps = [] - for _item in proto.steps: - ros_msg.steps.append(StaircaseStep()) - convert_proto_to_bosdyn_msgs_staircase_step(_item, ros_msg.steps[-1]) - - -def convert_bosdyn_msgs_staircase_to_proto(ros_msg: "bosdyn_msgs.msgs.Staircase", proto: "bosdyn.api.stairs_pb2.Staircase") -> None: - proto.Clear() - proto.knowledge_type = ros_msg.knowledge_type.value - if ros_msg.stair_tform_is_set: - convert_bosdyn_msgs_stair_transform_to_proto(ros_msg.stair_tform, proto.stair_tform) - proto.number_of_steps = ros_msg.number_of_steps - proto.average_rise = ros_msg.average_rise - proto.average_run = ros_msg.average_run - if ros_msg.average_width_is_set: - convert_bosdyn_msgs_staircase_width_to_proto(ros_msg.average_width, proto.average_width) - del proto.steps[:] - for _item in ros_msg.steps: - convert_bosdyn_msgs_staircase_step_to_proto(_item, proto.steps.add()) - - -def convert_proto_to_bosdyn_msgs_straight_staircase_one_of_location(proto: "bosdyn.api.stairs_pb2.StraightStaircase", ros_msg: "bosdyn_msgs.msgs.StraightStaircaseOneOfLocation") -> None: - if proto.HasField("from_ko_tform_stairs"): - ros_msg.location_choice = ros_msg.LOCATION_FROM_KO_TFORM_STAIRS_SET - convert_proto_to_geometry_msgs_pose(proto.from_ko_tform_stairs, ros_msg.from_ko_tform_stairs) - if proto.HasField("tform"): - ros_msg.location_choice = ros_msg.LOCATION_TFORM_SET - convert_proto_to_bosdyn_msgs_stair_transform(proto.tform, ros_msg.tform) - - -def convert_bosdyn_msgs_straight_staircase_one_of_location_to_proto(ros_msg: "bosdyn_msgs.msgs.StraightStaircaseOneOfLocation", proto: "bosdyn.api.stairs_pb2.StraightStaircase") -> None: - proto.ClearField("location") - if ros_msg.location_choice == ros_msg.LOCATION_FROM_KO_TFORM_STAIRS_SET: - convert_geometry_msgs_pose_to_proto(ros_msg.from_ko_tform_stairs, proto.from_ko_tform_stairs) - if ros_msg.location_choice == ros_msg.LOCATION_TFORM_SET: - convert_bosdyn_msgs_stair_transform_to_proto(ros_msg.tform, proto.tform) - - -def convert_proto_to_bosdyn_msgs_straight_staircase_stair(proto: "bosdyn.api.stairs_pb2.StraightStaircase.Stair", ros_msg: "bosdyn_msgs.msgs.StraightStaircaseStair") -> None: - ros_msg.rise = proto.rise - ros_msg.run = proto.run - - -def convert_bosdyn_msgs_straight_staircase_stair_to_proto(ros_msg: "bosdyn_msgs.msgs.StraightStaircaseStair", proto: "bosdyn.api.stairs_pb2.StraightStaircase.Stair") -> None: - proto.Clear() - proto.rise = ros_msg.rise - proto.run = ros_msg.run - - -def convert_proto_to_bosdyn_msgs_straight_staircase_landing(proto: "bosdyn.api.stairs_pb2.StraightStaircase.Landing", ros_msg: "bosdyn_msgs.msgs.StraightStaircaseLanding") -> None: - convert_proto_to_geometry_msgs_pose(proto.stairs_tform_landing_center, ros_msg.stairs_tform_landing_center) - ros_msg.stairs_tform_landing_center_is_set = proto.HasField("stairs_tform_landing_center") - ros_msg.landing_extent_x = proto.landing_extent_x - ros_msg.landing_extent_y = proto.landing_extent_y - - -def convert_bosdyn_msgs_straight_staircase_landing_to_proto(ros_msg: "bosdyn_msgs.msgs.StraightStaircaseLanding", proto: "bosdyn.api.stairs_pb2.StraightStaircase.Landing") -> None: - proto.Clear() - if ros_msg.stairs_tform_landing_center_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.stairs_tform_landing_center, proto.stairs_tform_landing_center) - proto.landing_extent_x = ros_msg.landing_extent_x - proto.landing_extent_y = ros_msg.landing_extent_y - - -def convert_proto_to_bosdyn_msgs_straight_staircase(proto: "bosdyn.api.stairs_pb2.StraightStaircase", ros_msg: "bosdyn_msgs.msgs.StraightStaircase") -> None: - convert_proto_to_bosdyn_msgs_straight_staircase_one_of_location(proto, ros_msg.location) - from bosdyn_msgs.msg import StraightStaircaseStair - ros_msg.stairs = [] - for _item in proto.stairs: - ros_msg.stairs.append(StraightStaircaseStair()) - convert_proto_to_bosdyn_msgs_straight_staircase_stair(_item, ros_msg.stairs[-1]) - convert_proto_to_bosdyn_msgs_straight_staircase_landing(proto.bottom_landing, ros_msg.bottom_landing) - ros_msg.bottom_landing_is_set = proto.HasField("bottom_landing") - convert_proto_to_bosdyn_msgs_straight_staircase_landing(proto.top_landing, ros_msg.top_landing) - ros_msg.top_landing_is_set = proto.HasField("top_landing") - - -def convert_bosdyn_msgs_straight_staircase_to_proto(ros_msg: "bosdyn_msgs.msgs.StraightStaircase", proto: "bosdyn.api.stairs_pb2.StraightStaircase") -> None: - proto.Clear() - convert_bosdyn_msgs_straight_staircase_one_of_location_to_proto(ros_msg.location, proto) - del proto.stairs[:] - for _item in ros_msg.stairs: - convert_bosdyn_msgs_straight_staircase_stair_to_proto(_item, proto.stairs.add()) - if ros_msg.bottom_landing_is_set: - convert_bosdyn_msgs_straight_staircase_landing_to_proto(ros_msg.bottom_landing, proto.bottom_landing) - if ros_msg.top_landing_is_set: - convert_bosdyn_msgs_straight_staircase_landing_to_proto(ros_msg.top_landing, proto.top_landing) - - -def convert_proto_to_bosdyn_msgs_staircase_landing(proto: "bosdyn.api.stairs_pb2.StaircaseLanding", ros_msg: "bosdyn_msgs.msgs.StaircaseLanding") -> None: - convert_proto_to_geometry_msgs_pose(proto.stairs_tform_landing_center, ros_msg.stairs_tform_landing_center) - ros_msg.stairs_tform_landing_center_is_set = proto.HasField("stairs_tform_landing_center") - ros_msg.landing_extent_x = proto.landing_extent_x - ros_msg.landing_extent_y = proto.landing_extent_y - - -def convert_bosdyn_msgs_staircase_landing_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseLanding", proto: "bosdyn.api.stairs_pb2.StaircaseLanding") -> None: - proto.Clear() - if ros_msg.stairs_tform_landing_center_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.stairs_tform_landing_center, proto.stairs_tform_landing_center) - proto.landing_extent_x = ros_msg.landing_extent_x - proto.landing_extent_y = ros_msg.landing_extent_y - - -def convert_proto_to_bosdyn_msgs_staircase_with_landings(proto: "bosdyn.api.stairs_pb2.StaircaseWithLandings", ros_msg: "bosdyn_msgs.msgs.StaircaseWithLandings") -> None: - convert_proto_to_bosdyn_msgs_staircase_landing(proto.bottom_landing, ros_msg.bottom_landing) - ros_msg.bottom_landing_is_set = proto.HasField("bottom_landing") - convert_proto_to_bosdyn_msgs_staircase(proto.staircase, ros_msg.staircase) - ros_msg.staircase_is_set = proto.HasField("staircase") - convert_proto_to_bosdyn_msgs_staircase_landing(proto.top_landing, ros_msg.top_landing) - ros_msg.top_landing_is_set = proto.HasField("top_landing") - - -def convert_bosdyn_msgs_staircase_with_landings_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseWithLandings", proto: "bosdyn.api.stairs_pb2.StaircaseWithLandings") -> None: - proto.Clear() - if ros_msg.bottom_landing_is_set: - convert_bosdyn_msgs_staircase_landing_to_proto(ros_msg.bottom_landing, proto.bottom_landing) - if ros_msg.staircase_is_set: - convert_bosdyn_msgs_staircase_to_proto(ros_msg.staircase, proto.staircase) - if ros_msg.top_landing_is_set: - convert_bosdyn_msgs_staircase_landing_to_proto(ros_msg.top_landing, proto.top_landing) - - -def convert_proto_to_bosdyn_msgs_synchronized_command_request(proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand.Request", ros_msg: "bosdyn_msgs.msgs.SynchronizedCommandRequest") -> None: - convert_proto_to_bosdyn_msgs_arm_command_request(proto.arm_command, ros_msg.arm_command) - ros_msg.arm_command_is_set = proto.HasField("arm_command") - convert_proto_to_bosdyn_msgs_mobility_command_request(proto.mobility_command, ros_msg.mobility_command) - ros_msg.mobility_command_is_set = proto.HasField("mobility_command") - convert_proto_to_bosdyn_msgs_gripper_command_request(proto.gripper_command, ros_msg.gripper_command) - ros_msg.gripper_command_is_set = proto.HasField("gripper_command") - - -def convert_bosdyn_msgs_synchronized_command_request_to_proto(ros_msg: "bosdyn_msgs.msgs.SynchronizedCommandRequest", proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand.Request") -> None: - proto.Clear() - if ros_msg.arm_command_is_set: - convert_bosdyn_msgs_arm_command_request_to_proto(ros_msg.arm_command, proto.arm_command) - if ros_msg.mobility_command_is_set: - convert_bosdyn_msgs_mobility_command_request_to_proto(ros_msg.mobility_command, proto.mobility_command) - if ros_msg.gripper_command_is_set: - convert_bosdyn_msgs_gripper_command_request_to_proto(ros_msg.gripper_command, proto.gripper_command) - - -def convert_proto_to_bosdyn_msgs_synchronized_command_feedback(proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand.Feedback", ros_msg: "bosdyn_msgs.msgs.SynchronizedCommandFeedback") -> None: - convert_proto_to_bosdyn_msgs_arm_command_feedback(proto.arm_command_feedback, ros_msg.arm_command_feedback) - ros_msg.arm_command_feedback_is_set = proto.HasField("arm_command_feedback") - convert_proto_to_bosdyn_msgs_mobility_command_feedback(proto.mobility_command_feedback, ros_msg.mobility_command_feedback) - ros_msg.mobility_command_feedback_is_set = proto.HasField("mobility_command_feedback") - convert_proto_to_bosdyn_msgs_gripper_command_feedback(proto.gripper_command_feedback, ros_msg.gripper_command_feedback) - ros_msg.gripper_command_feedback_is_set = proto.HasField("gripper_command_feedback") - - -def convert_bosdyn_msgs_synchronized_command_feedback_to_proto(ros_msg: "bosdyn_msgs.msgs.SynchronizedCommandFeedback", proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand.Feedback") -> None: - proto.Clear() - if ros_msg.arm_command_feedback_is_set: - convert_bosdyn_msgs_arm_command_feedback_to_proto(ros_msg.arm_command_feedback, proto.arm_command_feedback) - if ros_msg.mobility_command_feedback_is_set: - convert_bosdyn_msgs_mobility_command_feedback_to_proto(ros_msg.mobility_command_feedback, proto.mobility_command_feedback) - if ros_msg.gripper_command_feedback_is_set: - convert_bosdyn_msgs_gripper_command_feedback_to_proto(ros_msg.gripper_command_feedback, proto.gripper_command_feedback) - - -def convert_proto_to_bosdyn_msgs_synchronized_command(proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand", ros_msg: "bosdyn_msgs.msgs.SynchronizedCommand") -> None: - pass - - -def convert_bosdyn_msgs_synchronized_command_to_proto(ros_msg: "bosdyn_msgs.msgs.SynchronizedCommand", proto: "bosdyn.api.synchronized_command_pb2.SynchronizedCommand") -> None: - proto.Clear() - - -def convert_proto_to_bosdyn_msgs_time_range(proto: "bosdyn.api.time_range_pb2.TimeRange", ros_msg: "bosdyn_msgs.msgs.TimeRange") -> None: - convert_proto_to_builtin_interfaces_time(proto.start, ros_msg.start) - ros_msg.start_is_set = proto.HasField("start") - convert_proto_to_builtin_interfaces_time(proto.end, ros_msg.end) - ros_msg.end_is_set = proto.HasField("end") - - -def convert_bosdyn_msgs_time_range_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeRange", proto: "bosdyn.api.time_range_pb2.TimeRange") -> None: - proto.Clear() - if ros_msg.start_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.start, proto.start) - if ros_msg.end_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.end, proto.end) - - -def convert_proto_to_bosdyn_msgs_time_sync_round_trip(proto: "bosdyn.api.time_sync_pb2.TimeSyncRoundTrip", ros_msg: "bosdyn_msgs.msgs.TimeSyncRoundTrip") -> None: - convert_proto_to_builtin_interfaces_time(proto.client_tx, ros_msg.client_tx) - ros_msg.client_tx_is_set = proto.HasField("client_tx") - convert_proto_to_builtin_interfaces_time(proto.server_rx, ros_msg.server_rx) - ros_msg.server_rx_is_set = proto.HasField("server_rx") - convert_proto_to_builtin_interfaces_time(proto.server_tx, ros_msg.server_tx) - ros_msg.server_tx_is_set = proto.HasField("server_tx") - convert_proto_to_builtin_interfaces_time(proto.client_rx, ros_msg.client_rx) - ros_msg.client_rx_is_set = proto.HasField("client_rx") - - -def convert_bosdyn_msgs_time_sync_round_trip_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncRoundTrip", proto: "bosdyn.api.time_sync_pb2.TimeSyncRoundTrip") -> None: - proto.Clear() - if ros_msg.client_tx_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.client_tx, proto.client_tx) - if ros_msg.server_rx_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.server_rx, proto.server_rx) - if ros_msg.server_tx_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.server_tx, proto.server_tx) - if ros_msg.client_rx_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.client_rx, proto.client_rx) - - -def convert_proto_to_bosdyn_msgs_time_sync_estimate(proto: "bosdyn.api.time_sync_pb2.TimeSyncEstimate", ros_msg: "bosdyn_msgs.msgs.TimeSyncEstimate") -> None: - convert_proto_to_builtin_interfaces_duration(proto.round_trip_time, ros_msg.round_trip_time) - ros_msg.round_trip_time_is_set = proto.HasField("round_trip_time") - convert_proto_to_builtin_interfaces_duration(proto.clock_skew, ros_msg.clock_skew) - ros_msg.clock_skew_is_set = proto.HasField("clock_skew") - - -def convert_bosdyn_msgs_time_sync_estimate_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncEstimate", proto: "bosdyn.api.time_sync_pb2.TimeSyncEstimate") -> None: - proto.Clear() - if ros_msg.round_trip_time_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.round_trip_time, proto.round_trip_time) - if ros_msg.clock_skew_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.clock_skew, proto.clock_skew) - - -def convert_proto_to_bosdyn_msgs_time_sync_state_status(proto: "bosdyn.api.time_sync_pb2.TimeSyncState.Status", ros_msg: "bosdyn_msgs.msgs.TimeSyncStateStatus") -> None: - pass - - -def convert_bosdyn_msgs_time_sync_state_status_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncStateStatus", proto: "bosdyn.api.time_sync_pb2.TimeSyncState.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_time_sync_state(proto: "bosdyn.api.time_sync_pb2.TimeSyncState", ros_msg: "bosdyn_msgs.msgs.TimeSyncState") -> None: - convert_proto_to_bosdyn_msgs_time_sync_estimate(proto.best_estimate, ros_msg.best_estimate) - ros_msg.best_estimate_is_set = proto.HasField("best_estimate") - ros_msg.status.value = proto.status - convert_proto_to_builtin_interfaces_time(proto.measurement_time, ros_msg.measurement_time) - ros_msg.measurement_time_is_set = proto.HasField("measurement_time") - - -def convert_bosdyn_msgs_time_sync_state_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncState", proto: "bosdyn.api.time_sync_pb2.TimeSyncState") -> None: - proto.Clear() - if ros_msg.best_estimate_is_set: - convert_bosdyn_msgs_time_sync_estimate_to_proto(ros_msg.best_estimate, proto.best_estimate) - proto.status = ros_msg.status.value - if ros_msg.measurement_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.measurement_time, proto.measurement_time) - - -def convert_proto_to_bosdyn_msgs_time_sync_update_request(proto: "bosdyn.api.time_sync_pb2.TimeSyncUpdateRequest", ros_msg: "bosdyn_msgs.msgs.TimeSyncUpdateRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_time_sync_round_trip(proto.previous_round_trip, ros_msg.previous_round_trip) - ros_msg.previous_round_trip_is_set = proto.HasField("previous_round_trip") - ros_msg.clock_identifier = proto.clock_identifier - - -def convert_bosdyn_msgs_time_sync_update_request_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncUpdateRequest", proto: "bosdyn.api.time_sync_pb2.TimeSyncUpdateRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.previous_round_trip_is_set: - convert_bosdyn_msgs_time_sync_round_trip_to_proto(ros_msg.previous_round_trip, proto.previous_round_trip) - proto.clock_identifier = ros_msg.clock_identifier - - -def convert_proto_to_bosdyn_msgs_time_sync_update_response(proto: "bosdyn.api.time_sync_pb2.TimeSyncUpdateResponse", ros_msg: "bosdyn_msgs.msgs.TimeSyncUpdateResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_time_sync_estimate(proto.previous_estimate, ros_msg.previous_estimate) - ros_msg.previous_estimate_is_set = proto.HasField("previous_estimate") - convert_proto_to_bosdyn_msgs_time_sync_state(proto.state, ros_msg.state) - ros_msg.state_is_set = proto.HasField("state") - ros_msg.clock_identifier = proto.clock_identifier - - -def convert_bosdyn_msgs_time_sync_update_response_to_proto(ros_msg: "bosdyn_msgs.msgs.TimeSyncUpdateResponse", proto: "bosdyn.api.time_sync_pb2.TimeSyncUpdateResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - if ros_msg.previous_estimate_is_set: - convert_bosdyn_msgs_time_sync_estimate_to_proto(ros_msg.previous_estimate, proto.previous_estimate) - if ros_msg.state_is_set: - convert_bosdyn_msgs_time_sync_state_to_proto(ros_msg.state, proto.state) - proto.clock_identifier = ros_msg.clock_identifier - - -def convert_proto_to_bosdyn_msgs_positional_interpolation(proto: "bosdyn.api.trajectory_pb2.PositionalInterpolation", ros_msg: "bosdyn_msgs.msgs.PositionalInterpolation") -> None: - pass - - -def convert_bosdyn_msgs_positional_interpolation_to_proto(ros_msg: "bosdyn_msgs.msgs.PositionalInterpolation", proto: "bosdyn.api.trajectory_pb2.PositionalInterpolation") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_angular_interpolation(proto: "bosdyn.api.trajectory_pb2.AngularInterpolation", ros_msg: "bosdyn_msgs.msgs.AngularInterpolation") -> None: - pass - - -def convert_bosdyn_msgs_angular_interpolation_to_proto(ros_msg: "bosdyn_msgs.msgs.AngularInterpolation", proto: "bosdyn.api.trajectory_pb2.AngularInterpolation") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_se2_trajectory(proto: "bosdyn.api.trajectory_pb2.SE2Trajectory", ros_msg: "bosdyn_msgs.msgs.SE2Trajectory") -> None: - from bosdyn_msgs.msg import SE2TrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(SE2TrajectoryPoint()) - convert_proto_to_bosdyn_msgs_se2_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - ros_msg.interpolation.value = proto.interpolation - - -def convert_bosdyn_msgs_se2_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2Trajectory", proto: "bosdyn.api.trajectory_pb2.SE2Trajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_se2_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - proto.interpolation = ros_msg.interpolation.value - - -def convert_proto_to_bosdyn_msgs_se2_trajectory_point(proto: "bosdyn.api.trajectory_pb2.SE2TrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryPoint") -> None: - convert_proto_to_bosdyn_msgs_se2_pose(proto.pose, ros_msg.pose) - ros_msg.pose_is_set = proto.HasField("pose") - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_se2_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.SE2TrajectoryPoint", proto: "bosdyn.api.trajectory_pb2.SE2TrajectoryPoint") -> None: - proto.Clear() - if ros_msg.pose_is_set: - convert_bosdyn_msgs_se2_pose_to_proto(ros_msg.pose, proto.pose) - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_se3_trajectory(proto: "bosdyn.api.trajectory_pb2.SE3Trajectory", ros_msg: "bosdyn_msgs.msgs.SE3Trajectory") -> None: - from bosdyn_msgs.msg import SE3TrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(SE3TrajectoryPoint()) - convert_proto_to_bosdyn_msgs_se3_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - ros_msg.pos_interpolation.value = proto.pos_interpolation - ros_msg.ang_interpolation.value = proto.ang_interpolation - - -def convert_bosdyn_msgs_se3_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.SE3Trajectory", proto: "bosdyn.api.trajectory_pb2.SE3Trajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_se3_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - proto.pos_interpolation = ros_msg.pos_interpolation.value - proto.ang_interpolation = ros_msg.ang_interpolation.value - - -def convert_proto_to_bosdyn_msgs_se3_trajectory_point(proto: "bosdyn.api.trajectory_pb2.SE3TrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.SE3TrajectoryPoint") -> None: - convert_proto_to_geometry_msgs_pose(proto.pose, ros_msg.pose) - ros_msg.pose_is_set = proto.HasField("pose") - convert_proto_to_geometry_msgs_twist(proto.velocity, ros_msg.velocity) - ros_msg.velocity_is_set = proto.HasField("velocity") - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_se3_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.SE3TrajectoryPoint", proto: "bosdyn.api.trajectory_pb2.SE3TrajectoryPoint") -> None: - proto.Clear() - if ros_msg.pose_is_set: - convert_geometry_msgs_pose_to_proto(ros_msg.pose, proto.pose) - if ros_msg.velocity_is_set: - convert_geometry_msgs_twist_to_proto(ros_msg.velocity, proto.velocity) - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_vec3_trajectory(proto: "bosdyn.api.trajectory_pb2.Vec3Trajectory", ros_msg: "bosdyn_msgs.msgs.Vec3Trajectory") -> None: - from bosdyn_msgs.msg import Vec3TrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(Vec3TrajectoryPoint()) - convert_proto_to_bosdyn_msgs_vec3_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - ros_msg.pos_interpolation.value = proto.pos_interpolation - convert_proto_to_geometry_msgs_vector3(proto.starting_velocity, ros_msg.starting_velocity) - ros_msg.starting_velocity_is_set = proto.HasField("starting_velocity") - convert_proto_to_geometry_msgs_vector3(proto.ending_velocity, ros_msg.ending_velocity) - ros_msg.ending_velocity_is_set = proto.HasField("ending_velocity") - - -def convert_bosdyn_msgs_vec3_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec3Trajectory", proto: "bosdyn.api.trajectory_pb2.Vec3Trajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_vec3_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - proto.pos_interpolation = ros_msg.pos_interpolation.value - if ros_msg.starting_velocity_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.starting_velocity, proto.starting_velocity) - if ros_msg.ending_velocity_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.ending_velocity, proto.ending_velocity) - - -def convert_proto_to_bosdyn_msgs_vec3_trajectory_point(proto: "bosdyn.api.trajectory_pb2.Vec3TrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.Vec3TrajectoryPoint") -> None: - convert_proto_to_geometry_msgs_vector3(proto.point, ros_msg.point) - ros_msg.point_is_set = proto.HasField("point") - ros_msg.linear_speed = proto.linear_speed - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_vec3_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.Vec3TrajectoryPoint", proto: "bosdyn.api.trajectory_pb2.Vec3TrajectoryPoint") -> None: - proto.Clear() - if ros_msg.point_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.point, proto.point) - proto.linear_speed = ros_msg.linear_speed - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_wrench_trajectory(proto: "bosdyn.api.trajectory_pb2.WrenchTrajectory", ros_msg: "bosdyn_msgs.msgs.WrenchTrajectory") -> None: - from bosdyn_msgs.msg import WrenchTrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(WrenchTrajectoryPoint()) - convert_proto_to_bosdyn_msgs_wrench_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - - -def convert_bosdyn_msgs_wrench_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.WrenchTrajectory", proto: "bosdyn.api.trajectory_pb2.WrenchTrajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_wrench_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - - -def convert_proto_to_bosdyn_msgs_wrench_trajectory_point(proto: "bosdyn.api.trajectory_pb2.WrenchTrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.WrenchTrajectoryPoint") -> None: - convert_proto_to_geometry_msgs_wrench(proto.wrench, ros_msg.wrench) - ros_msg.wrench_is_set = proto.HasField("wrench") - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_wrench_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.WrenchTrajectoryPoint", proto: "bosdyn.api.trajectory_pb2.WrenchTrajectoryPoint") -> None: - proto.Clear() - if ros_msg.wrench_is_set: - convert_geometry_msgs_wrench_to_proto(ros_msg.wrench, proto.wrench) - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_scalar_trajectory(proto: "bosdyn.api.trajectory_pb2.ScalarTrajectory", ros_msg: "bosdyn_msgs.msgs.ScalarTrajectory") -> None: - from bosdyn_msgs.msg import ScalarTrajectoryPoint - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(ScalarTrajectoryPoint()) - convert_proto_to_bosdyn_msgs_scalar_trajectory_point(_item, ros_msg.points[-1]) - convert_proto_to_builtin_interfaces_time(proto.reference_time, ros_msg.reference_time) - ros_msg.reference_time_is_set = proto.HasField("reference_time") - ros_msg.interpolation.value = proto.interpolation - - -def convert_bosdyn_msgs_scalar_trajectory_to_proto(ros_msg: "bosdyn_msgs.msgs.ScalarTrajectory", proto: "bosdyn.api.trajectory_pb2.ScalarTrajectory") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_bosdyn_msgs_scalar_trajectory_point_to_proto(_item, proto.points.add()) - if ros_msg.reference_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.reference_time, proto.reference_time) - proto.interpolation = ros_msg.interpolation.value - - -def convert_proto_to_bosdyn_msgs_scalar_trajectory_point(proto: "bosdyn.api.trajectory_pb2.ScalarTrajectoryPoint", ros_msg: "bosdyn_msgs.msgs.ScalarTrajectoryPoint") -> None: - ros_msg.point = proto.point - ros_msg.velocity = proto.velocity.value - ros_msg.velocity_is_set = proto.HasField("velocity") - convert_proto_to_builtin_interfaces_duration(proto.time_since_reference, ros_msg.time_since_reference) - ros_msg.time_since_reference_is_set = proto.HasField("time_since_reference") - - -def convert_bosdyn_msgs_scalar_trajectory_point_to_proto(ros_msg: "bosdyn_msgs.msgs.ScalarTrajectoryPoint", proto: "bosdyn.api.trajectory_pb2.ScalarTrajectoryPoint") -> None: - proto.Clear() - proto.point = ros_msg.point - if ros_msg.velocity_is_set: - convert_float64_to_proto(ros_msg.velocity, proto.velocity) - if ros_msg.time_since_reference_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.time_since_reference, proto.time_since_reference) - - -def convert_proto_to_bosdyn_msgs_temperature_enum(proto: "bosdyn.api.units_pb2.TemperatureEnum", ros_msg: "bosdyn_msgs.msgs.TemperatureEnum") -> None: - pass - - -def convert_bosdyn_msgs_temperature_enum_to_proto(ros_msg: "bosdyn_msgs.msgs.TemperatureEnum", proto: "bosdyn.api.units_pb2.TemperatureEnum") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_pressure_enum(proto: "bosdyn.api.units_pb2.PressureEnum", ros_msg: "bosdyn_msgs.msgs.PressureEnum") -> None: - pass - - -def convert_bosdyn_msgs_pressure_enum_to_proto(ros_msg: "bosdyn_msgs.msgs.PressureEnum", proto: "bosdyn.api.units_pb2.PressureEnum") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_units_one_of_units(proto: "bosdyn.api.units_pb2.Units", ros_msg: "bosdyn_msgs.msgs.UnitsOneOfUnits") -> None: - if proto.HasField("name"): - ros_msg.units_choice = ros_msg.UNITS_NAME_SET - ros_msg.name = proto.name - if proto.HasField("temp"): - ros_msg.units_choice = ros_msg.UNITS_TEMP_SET - ros_msg.temp.value = proto.temp - if proto.HasField("press"): - ros_msg.units_choice = ros_msg.UNITS_PRESS_SET - ros_msg.press.value = proto.press - - -def convert_bosdyn_msgs_units_one_of_units_to_proto(ros_msg: "bosdyn_msgs.msgs.UnitsOneOfUnits", proto: "bosdyn.api.units_pb2.Units") -> None: - proto.ClearField("units") - if ros_msg.units_choice == ros_msg.UNITS_NAME_SET: - proto.name = ros_msg.name - if ros_msg.units_choice == ros_msg.UNITS_TEMP_SET: - proto.temp = ros_msg.temp.value - if ros_msg.units_choice == ros_msg.UNITS_PRESS_SET: - proto.press = ros_msg.press.value - - -def convert_proto_to_bosdyn_msgs_units(proto: "bosdyn.api.units_pb2.Units", ros_msg: "bosdyn_msgs.msgs.Units") -> None: - convert_proto_to_bosdyn_msgs_units_one_of_units(proto, ros_msg.units) - ros_msg.is_relative = proto.is_relative - - -def convert_bosdyn_msgs_units_to_proto(ros_msg: "bosdyn_msgs.msgs.Units", proto: "bosdyn.api.units_pb2.Units") -> None: - proto.Clear() - convert_bosdyn_msgs_units_one_of_units_to_proto(ros_msg.units, proto) - proto.is_relative = ros_msg.is_relative - - -def convert_proto_to_bosdyn_msgs_world_object(proto: "bosdyn.api.world_object_pb2.WorldObject", ros_msg: "bosdyn_msgs.msgs.WorldObject") -> None: - ros_msg.id = proto.id - ros_msg.name = proto.name - convert_proto_to_builtin_interfaces_time(proto.acquisition_time, ros_msg.acquisition_time) - ros_msg.acquisition_time_is_set = proto.HasField("acquisition_time") - convert_proto_to_bosdyn_msgs_frame_tree_snapshot(proto.transforms_snapshot, ros_msg.transforms_snapshot) - ros_msg.transforms_snapshot_is_set = proto.HasField("transforms_snapshot") - convert_proto_to_builtin_interfaces_duration(proto.object_lifetime, ros_msg.object_lifetime) - ros_msg.object_lifetime_is_set = proto.HasField("object_lifetime") - from bosdyn_msgs.msg import DrawableProperties - ros_msg.drawable_properties = [] - for _item in proto.drawable_properties: - ros_msg.drawable_properties.append(DrawableProperties()) - convert_proto_to_bosdyn_msgs_drawable_properties(_item, ros_msg.drawable_properties[-1]) - convert_proto_to_bosdyn_msgs_april_tag_properties(proto.apriltag_properties, ros_msg.apriltag_properties) - ros_msg.apriltag_properties_is_set = proto.HasField("apriltag_properties") - convert_proto_to_bosdyn_msgs_no_go_region_properties(proto.nogo_region_properties, ros_msg.nogo_region_properties) - ros_msg.nogo_region_properties_is_set = proto.HasField("nogo_region_properties") - convert_proto_to_bosdyn_msgs_image_properties(proto.image_properties, ros_msg.image_properties) - ros_msg.image_properties_is_set = proto.HasField("image_properties") - convert_proto_to_bosdyn_msgs_dock_properties(proto.dock_properties, ros_msg.dock_properties) - ros_msg.dock_properties_is_set = proto.HasField("dock_properties") - convert_proto_to_bosdyn_msgs_ray_properties(proto.ray_properties, ros_msg.ray_properties) - ros_msg.ray_properties_is_set = proto.HasField("ray_properties") - convert_proto_to_bosdyn_msgs_bounding_box_properties(proto.bounding_box_properties, ros_msg.bounding_box_properties) - ros_msg.bounding_box_properties_is_set = proto.HasField("bounding_box_properties") - convert_proto_to_bosdyn_msgs_staircase_properties(proto.staircase_properties, ros_msg.staircase_properties) - ros_msg.staircase_properties_is_set = proto.HasField("staircase_properties") - - -def convert_bosdyn_msgs_world_object_to_proto(ros_msg: "bosdyn_msgs.msgs.WorldObject", proto: "bosdyn.api.world_object_pb2.WorldObject") -> None: - proto.Clear() - proto.id = ros_msg.id - proto.name = ros_msg.name - if ros_msg.acquisition_time_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.acquisition_time, proto.acquisition_time) - if ros_msg.transforms_snapshot_is_set: - convert_bosdyn_msgs_frame_tree_snapshot_to_proto(ros_msg.transforms_snapshot, proto.transforms_snapshot) - if ros_msg.object_lifetime_is_set: - convert_builtin_interfaces_duration_to_proto(ros_msg.object_lifetime, proto.object_lifetime) - del proto.drawable_properties[:] - for _item in ros_msg.drawable_properties: - convert_bosdyn_msgs_drawable_properties_to_proto(_item, proto.drawable_properties.add()) - if ros_msg.apriltag_properties_is_set: - convert_bosdyn_msgs_april_tag_properties_to_proto(ros_msg.apriltag_properties, proto.apriltag_properties) - if ros_msg.nogo_region_properties_is_set: - convert_bosdyn_msgs_no_go_region_properties_to_proto(ros_msg.nogo_region_properties, proto.nogo_region_properties) - if ros_msg.image_properties_is_set: - convert_bosdyn_msgs_image_properties_to_proto(ros_msg.image_properties, proto.image_properties) - if ros_msg.dock_properties_is_set: - convert_bosdyn_msgs_dock_properties_to_proto(ros_msg.dock_properties, proto.dock_properties) - if ros_msg.ray_properties_is_set: - convert_bosdyn_msgs_ray_properties_to_proto(ros_msg.ray_properties, proto.ray_properties) - if ros_msg.bounding_box_properties_is_set: - convert_bosdyn_msgs_bounding_box_properties_to_proto(ros_msg.bounding_box_properties, proto.bounding_box_properties) - if ros_msg.staircase_properties_is_set: - convert_bosdyn_msgs_staircase_properties_to_proto(ros_msg.staircase_properties, proto.staircase_properties) - - -def convert_proto_to_bosdyn_msgs_world_object_type(proto: "bosdyn.api.world_object_pb2.WorldObjectType", ros_msg: "bosdyn_msgs.msgs.WorldObjectType") -> None: - pass - - -def convert_bosdyn_msgs_world_object_type_to_proto(ros_msg: "bosdyn_msgs.msgs.WorldObjectType", proto: "bosdyn.api.world_object_pb2.WorldObjectType") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_list_world_object_request(proto: "bosdyn.api.world_object_pb2.ListWorldObjectRequest", ros_msg: "bosdyn_msgs.msgs.ListWorldObjectRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import WorldObjectType - ros_msg.object_type = [] - for _item in proto.object_type: - ros_msg.object_type.append(WorldObjectType()) - ros_msg.object_type[-1].value = _item - convert_proto_to_builtin_interfaces_time(proto.timestamp_filter, ros_msg.timestamp_filter) - ros_msg.timestamp_filter_is_set = proto.HasField("timestamp_filter") - - -def convert_bosdyn_msgs_list_world_object_request_to_proto(ros_msg: "bosdyn_msgs.msgs.ListWorldObjectRequest", proto: "bosdyn.api.world_object_pb2.ListWorldObjectRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - del proto.object_type[:] - for _item in ros_msg.object_type: - proto.object_type.append(_item.value) - if ros_msg.timestamp_filter_is_set: - convert_builtin_interfaces_time_to_proto(ros_msg.timestamp_filter, proto.timestamp_filter) - - -def convert_proto_to_bosdyn_msgs_list_world_object_response(proto: "bosdyn.api.world_object_pb2.ListWorldObjectResponse", ros_msg: "bosdyn_msgs.msgs.ListWorldObjectResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - from bosdyn_msgs.msg import WorldObject - ros_msg.world_objects = [] - for _item in proto.world_objects: - ros_msg.world_objects.append(WorldObject()) - convert_proto_to_bosdyn_msgs_world_object(_item, ros_msg.world_objects[-1]) - - -def convert_bosdyn_msgs_list_world_object_response_to_proto(ros_msg: "bosdyn_msgs.msgs.ListWorldObjectResponse", proto: "bosdyn.api.world_object_pb2.ListWorldObjectResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - del proto.world_objects[:] - for _item in ros_msg.world_objects: - convert_bosdyn_msgs_world_object_to_proto(_item, proto.world_objects.add()) - - -def convert_proto_to_bosdyn_msgs_mutate_world_object_request_action(proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest.Action", ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequestAction") -> None: - pass - - -def convert_bosdyn_msgs_mutate_world_object_request_action_to_proto(ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequestAction", proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest.Action") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_mutate_world_object_request_mutation(proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest.Mutation", ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequestMutation") -> None: - ros_msg.action.value = proto.action - convert_proto_to_bosdyn_msgs_world_object(proto.object, ros_msg.object) - ros_msg.object_is_set = proto.HasField("object") - - -def convert_bosdyn_msgs_mutate_world_object_request_mutation_to_proto(ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequestMutation", proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest.Mutation") -> None: - proto.Clear() - proto.action = ros_msg.action.value - if ros_msg.object_is_set: - convert_bosdyn_msgs_world_object_to_proto(ros_msg.object, proto.object) - - -def convert_proto_to_bosdyn_msgs_mutate_world_object_request(proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest", ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequest") -> None: - convert_proto_to_bosdyn_msgs_request_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - convert_proto_to_bosdyn_msgs_mutate_world_object_request_mutation(proto.mutation, ros_msg.mutation) - ros_msg.mutation_is_set = proto.HasField("mutation") - - -def convert_bosdyn_msgs_mutate_world_object_request_to_proto(ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectRequest", proto: "bosdyn.api.world_object_pb2.MutateWorldObjectRequest") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_request_header_to_proto(ros_msg.header, proto.header) - if ros_msg.mutation_is_set: - convert_bosdyn_msgs_mutate_world_object_request_mutation_to_proto(ros_msg.mutation, proto.mutation) - - -def convert_proto_to_bosdyn_msgs_mutate_world_object_response_status(proto: "bosdyn.api.world_object_pb2.MutateWorldObjectResponse.Status", ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectResponseStatus") -> None: - pass - - -def convert_bosdyn_msgs_mutate_world_object_response_status_to_proto(ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectResponseStatus", proto: "bosdyn.api.world_object_pb2.MutateWorldObjectResponse.Status") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_mutate_world_object_response(proto: "bosdyn.api.world_object_pb2.MutateWorldObjectResponse", ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectResponse") -> None: - convert_proto_to_bosdyn_msgs_response_header(proto.header, ros_msg.header) - ros_msg.header_is_set = proto.HasField("header") - ros_msg.status.value = proto.status - ros_msg.mutated_object_id = proto.mutated_object_id - - -def convert_bosdyn_msgs_mutate_world_object_response_to_proto(ros_msg: "bosdyn_msgs.msgs.MutateWorldObjectResponse", proto: "bosdyn.api.world_object_pb2.MutateWorldObjectResponse") -> None: - proto.Clear() - if ros_msg.header_is_set: - convert_bosdyn_msgs_response_header_to_proto(ros_msg.header, proto.header) - proto.status = ros_msg.status.value - proto.mutated_object_id = ros_msg.mutated_object_id - - -def convert_proto_to_bosdyn_msgs_no_go_region_properties_one_of_region(proto: "bosdyn.api.world_object_pb2.NoGoRegionProperties", ros_msg: "bosdyn_msgs.msgs.NoGoRegionPropertiesOneOfRegion") -> None: - if proto.HasField("box"): - ros_msg.region_choice = ros_msg.REGION_BOX_SET - convert_proto_to_bosdyn_msgs_box2_with_frame(proto.box, ros_msg.box) - - -def convert_bosdyn_msgs_no_go_region_properties_one_of_region_to_proto(ros_msg: "bosdyn_msgs.msgs.NoGoRegionPropertiesOneOfRegion", proto: "bosdyn.api.world_object_pb2.NoGoRegionProperties") -> None: - proto.ClearField("region") - if ros_msg.region_choice == ros_msg.REGION_BOX_SET: - convert_bosdyn_msgs_box2_with_frame_to_proto(ros_msg.box, proto.box) - - -def convert_proto_to_bosdyn_msgs_no_go_region_properties(proto: "bosdyn.api.world_object_pb2.NoGoRegionProperties", ros_msg: "bosdyn_msgs.msgs.NoGoRegionProperties") -> None: - convert_proto_to_bosdyn_msgs_no_go_region_properties_one_of_region(proto, ros_msg.region) - ros_msg.disable_foot_obstacle_generation = proto.disable_foot_obstacle_generation - ros_msg.disable_body_obstacle_generation = proto.disable_body_obstacle_generation - ros_msg.disable_foot_obstacle_inflation = proto.disable_foot_obstacle_inflation - - -def convert_bosdyn_msgs_no_go_region_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.NoGoRegionProperties", proto: "bosdyn.api.world_object_pb2.NoGoRegionProperties") -> None: - proto.Clear() - convert_bosdyn_msgs_no_go_region_properties_one_of_region_to_proto(ros_msg.region, proto) - proto.disable_foot_obstacle_generation = ros_msg.disable_foot_obstacle_generation - proto.disable_body_obstacle_generation = ros_msg.disable_body_obstacle_generation - proto.disable_foot_obstacle_inflation = ros_msg.disable_foot_obstacle_inflation - - -def convert_proto_to_bosdyn_msgs_image_properties_one_of_image_data(proto: "bosdyn.api.world_object_pb2.ImageProperties", ros_msg: "bosdyn_msgs.msgs.ImagePropertiesOneOfImageData") -> None: - if proto.HasField("coordinates"): - ros_msg.image_data_choice = ros_msg.IMAGE_DATA_COORDINATES_SET - convert_proto_to_bosdyn_msgs_polygon(proto.coordinates, ros_msg.coordinates) - if proto.HasField("keypoints"): - ros_msg.image_data_choice = ros_msg.IMAGE_DATA_KEYPOINTS_SET - convert_proto_to_bosdyn_msgs_keypoint_set(proto.keypoints, ros_msg.keypoints) - - -def convert_bosdyn_msgs_image_properties_one_of_image_data_to_proto(ros_msg: "bosdyn_msgs.msgs.ImagePropertiesOneOfImageData", proto: "bosdyn.api.world_object_pb2.ImageProperties") -> None: - proto.ClearField("image_data") - if ros_msg.image_data_choice == ros_msg.IMAGE_DATA_COORDINATES_SET: - convert_bosdyn_msgs_polygon_to_proto(ros_msg.coordinates, proto.coordinates) - if ros_msg.image_data_choice == ros_msg.IMAGE_DATA_KEYPOINTS_SET: - convert_bosdyn_msgs_keypoint_set_to_proto(ros_msg.keypoints, proto.keypoints) - - -def convert_proto_to_bosdyn_msgs_image_properties(proto: "bosdyn.api.world_object_pb2.ImageProperties", ros_msg: "bosdyn_msgs.msgs.ImageProperties") -> None: - ros_msg.camera_source = proto.camera_source - convert_proto_to_bosdyn_msgs_image_properties_one_of_image_data(proto, ros_msg.image_data) - convert_proto_to_bosdyn_msgs_image_source(proto.image_source, ros_msg.image_source) - ros_msg.image_source_is_set = proto.HasField("image_source") - convert_proto_to_bosdyn_msgs_image_capture(proto.image_capture, ros_msg.image_capture) - ros_msg.image_capture_is_set = proto.HasField("image_capture") - ros_msg.frame_name_image_coordinates = proto.frame_name_image_coordinates - - -def convert_bosdyn_msgs_image_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.ImageProperties", proto: "bosdyn.api.world_object_pb2.ImageProperties") -> None: - proto.Clear() - proto.camera_source = ros_msg.camera_source - convert_bosdyn_msgs_image_properties_one_of_image_data_to_proto(ros_msg.image_data, proto) - if ros_msg.image_source_is_set: - convert_bosdyn_msgs_image_source_to_proto(ros_msg.image_source, proto.image_source) - if ros_msg.image_capture_is_set: - convert_bosdyn_msgs_image_capture_to_proto(ros_msg.image_capture, proto.image_capture) - proto.frame_name_image_coordinates = ros_msg.frame_name_image_coordinates - - -def convert_proto_to_bosdyn_msgs_dock_properties(proto: "bosdyn.api.world_object_pb2.DockProperties", ros_msg: "bosdyn_msgs.msgs.DockProperties") -> None: - ros_msg.dock_id = proto.dock_id - ros_msg.type.value = proto.type - ros_msg.frame_name_dock = proto.frame_name_dock - ros_msg.unavailable = proto.unavailable - ros_msg.from_prior = proto.from_prior - - -def convert_bosdyn_msgs_dock_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.DockProperties", proto: "bosdyn.api.world_object_pb2.DockProperties") -> None: - proto.Clear() - proto.dock_id = ros_msg.dock_id - proto.type = ros_msg.type.value - proto.frame_name_dock = ros_msg.frame_name_dock - proto.unavailable = ros_msg.unavailable - proto.from_prior = ros_msg.from_prior - - -def convert_proto_to_bosdyn_msgs_april_tag_properties_april_tag_pose_status(proto: "bosdyn.api.world_object_pb2.AprilTagProperties.AprilTagPoseStatus", ros_msg: "bosdyn_msgs.msgs.AprilTagPropertiesAprilTagPoseStatus") -> None: - pass - - -def convert_bosdyn_msgs_april_tag_properties_april_tag_pose_status_to_proto(ros_msg: "bosdyn_msgs.msgs.AprilTagPropertiesAprilTagPoseStatus", proto: "bosdyn.api.world_object_pb2.AprilTagProperties.AprilTagPoseStatus") -> None: - pass - - -def convert_proto_to_bosdyn_msgs_april_tag_properties(proto: "bosdyn.api.world_object_pb2.AprilTagProperties", ros_msg: "bosdyn_msgs.msgs.AprilTagProperties") -> None: - ros_msg.tag_id = proto.tag_id - convert_proto_to_bosdyn_msgs_vec2(proto.dimensions, ros_msg.dimensions) - ros_msg.dimensions_is_set = proto.HasField("dimensions") - ros_msg.frame_name_fiducial = proto.frame_name_fiducial - ros_msg.fiducial_pose_status.value = proto.fiducial_pose_status - ros_msg.frame_name_fiducial_filtered = proto.frame_name_fiducial_filtered - ros_msg.fiducial_filtered_pose_status.value = proto.fiducial_filtered_pose_status - ros_msg.frame_name_camera = proto.frame_name_camera - convert_proto_to_bosdyn_msgs_se3_covariance(proto.detection_covariance, ros_msg.detection_covariance) - ros_msg.detection_covariance_is_set = proto.HasField("detection_covariance") - ros_msg.detection_covariance_reference_frame = proto.detection_covariance_reference_frame - - -def convert_bosdyn_msgs_april_tag_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.AprilTagProperties", proto: "bosdyn.api.world_object_pb2.AprilTagProperties") -> None: - proto.Clear() - proto.tag_id = ros_msg.tag_id - if ros_msg.dimensions_is_set: - convert_bosdyn_msgs_vec2_to_proto(ros_msg.dimensions, proto.dimensions) - proto.frame_name_fiducial = ros_msg.frame_name_fiducial - proto.fiducial_pose_status = ros_msg.fiducial_pose_status.value - proto.frame_name_fiducial_filtered = ros_msg.frame_name_fiducial_filtered - proto.fiducial_filtered_pose_status = ros_msg.fiducial_filtered_pose_status.value - proto.frame_name_camera = ros_msg.frame_name_camera - if ros_msg.detection_covariance_is_set: - convert_bosdyn_msgs_se3_covariance_to_proto(ros_msg.detection_covariance, proto.detection_covariance) - proto.detection_covariance_reference_frame = ros_msg.detection_covariance_reference_frame - - -def convert_proto_to_bosdyn_msgs_ray_properties(proto: "bosdyn.api.world_object_pb2.RayProperties", ros_msg: "bosdyn_msgs.msgs.RayProperties") -> None: - convert_proto_to_bosdyn_msgs_ray(proto.ray, ros_msg.ray) - ros_msg.ray_is_set = proto.HasField("ray") - ros_msg.frame = proto.frame - - -def convert_bosdyn_msgs_ray_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.RayProperties", proto: "bosdyn.api.world_object_pb2.RayProperties") -> None: - proto.Clear() - if ros_msg.ray_is_set: - convert_bosdyn_msgs_ray_to_proto(ros_msg.ray, proto.ray) - proto.frame = ros_msg.frame - - -def convert_proto_to_bosdyn_msgs_bounding_box_properties(proto: "bosdyn.api.world_object_pb2.BoundingBoxProperties", ros_msg: "bosdyn_msgs.msgs.BoundingBoxProperties") -> None: - convert_proto_to_geometry_msgs_vector3(proto.size_ewrt_frame, ros_msg.size_ewrt_frame) - ros_msg.size_ewrt_frame_is_set = proto.HasField("size_ewrt_frame") - ros_msg.frame = proto.frame - - -def convert_bosdyn_msgs_bounding_box_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.BoundingBoxProperties", proto: "bosdyn.api.world_object_pb2.BoundingBoxProperties") -> None: - proto.Clear() - if ros_msg.size_ewrt_frame_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.size_ewrt_frame, proto.size_ewrt_frame) - proto.frame = ros_msg.frame - - -def convert_proto_to_bosdyn_msgs_drawable_properties_color(proto: "bosdyn.api.world_object_pb2.DrawableProperties.Color", ros_msg: "bosdyn_msgs.msgs.DrawablePropertiesColor") -> None: - ros_msg.r = proto.r - ros_msg.g = proto.g - ros_msg.b = proto.b - ros_msg.a = proto.a - - -def convert_bosdyn_msgs_drawable_properties_color_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawablePropertiesColor", proto: "bosdyn.api.world_object_pb2.DrawableProperties.Color") -> None: - proto.Clear() - proto.r = ros_msg.r - proto.g = ros_msg.g - proto.b = ros_msg.b - proto.a = ros_msg.a - - -def convert_proto_to_bosdyn_msgs_drawable_properties_one_of_drawable(proto: "bosdyn.api.world_object_pb2.DrawableProperties", ros_msg: "bosdyn_msgs.msgs.DrawablePropertiesOneOfDrawable") -> None: - if proto.HasField("frame"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_FRAME_SET - convert_proto_to_bosdyn_msgs_drawable_frame(proto.frame, ros_msg.frame) - if proto.HasField("sphere"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_SPHERE_SET - convert_proto_to_bosdyn_msgs_drawable_sphere(proto.sphere, ros_msg.sphere) - if proto.HasField("box"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_BOX_SET - convert_proto_to_bosdyn_msgs_drawable_box(proto.box, ros_msg.box) - if proto.HasField("arrow"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_ARROW_SET - convert_proto_to_bosdyn_msgs_drawable_arrow(proto.arrow, ros_msg.arrow) - if proto.HasField("capsule"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_CAPSULE_SET - convert_proto_to_bosdyn_msgs_drawable_capsule(proto.capsule, ros_msg.capsule) - if proto.HasField("cylinder"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_CYLINDER_SET - convert_proto_to_bosdyn_msgs_drawable_cylinder(proto.cylinder, ros_msg.cylinder) - if proto.HasField("linestrip"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_LINESTRIP_SET - convert_proto_to_bosdyn_msgs_drawable_line_strip(proto.linestrip, ros_msg.linestrip) - if proto.HasField("points"): - ros_msg.drawable_choice = ros_msg.DRAWABLE_POINTS_SET - convert_proto_to_bosdyn_msgs_drawable_points(proto.points, ros_msg.points) - - -def convert_bosdyn_msgs_drawable_properties_one_of_drawable_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawablePropertiesOneOfDrawable", proto: "bosdyn.api.world_object_pb2.DrawableProperties") -> None: - proto.ClearField("drawable") - if ros_msg.drawable_choice == ros_msg.DRAWABLE_FRAME_SET: - convert_bosdyn_msgs_drawable_frame_to_proto(ros_msg.frame, proto.frame) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_SPHERE_SET: - convert_bosdyn_msgs_drawable_sphere_to_proto(ros_msg.sphere, proto.sphere) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_BOX_SET: - convert_bosdyn_msgs_drawable_box_to_proto(ros_msg.box, proto.box) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_ARROW_SET: - convert_bosdyn_msgs_drawable_arrow_to_proto(ros_msg.arrow, proto.arrow) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_CAPSULE_SET: - convert_bosdyn_msgs_drawable_capsule_to_proto(ros_msg.capsule, proto.capsule) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_CYLINDER_SET: - convert_bosdyn_msgs_drawable_cylinder_to_proto(ros_msg.cylinder, proto.cylinder) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_LINESTRIP_SET: - convert_bosdyn_msgs_drawable_line_strip_to_proto(ros_msg.linestrip, proto.linestrip) - if ros_msg.drawable_choice == ros_msg.DRAWABLE_POINTS_SET: - convert_bosdyn_msgs_drawable_points_to_proto(ros_msg.points, proto.points) - - -def convert_proto_to_bosdyn_msgs_drawable_properties(proto: "bosdyn.api.world_object_pb2.DrawableProperties", ros_msg: "bosdyn_msgs.msgs.DrawableProperties") -> None: - convert_proto_to_bosdyn_msgs_drawable_properties_color(proto.color, ros_msg.color) - ros_msg.color_is_set = proto.HasField("color") - ros_msg.label = proto.label - ros_msg.wireframe = proto.wireframe - convert_proto_to_bosdyn_msgs_drawable_properties_one_of_drawable(proto, ros_msg.drawable) - ros_msg.frame_name_drawable = proto.frame_name_drawable - - -def convert_bosdyn_msgs_drawable_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableProperties", proto: "bosdyn.api.world_object_pb2.DrawableProperties") -> None: - proto.Clear() - if ros_msg.color_is_set: - convert_bosdyn_msgs_drawable_properties_color_to_proto(ros_msg.color, proto.color) - proto.label = ros_msg.label - proto.wireframe = ros_msg.wireframe - convert_bosdyn_msgs_drawable_properties_one_of_drawable_to_proto(ros_msg.drawable, proto) - proto.frame_name_drawable = ros_msg.frame_name_drawable - - -def convert_proto_to_bosdyn_msgs_staircase_properties(proto: "bosdyn.api.world_object_pb2.StaircaseProperties", ros_msg: "bosdyn_msgs.msgs.StaircaseProperties") -> None: - convert_proto_to_bosdyn_msgs_staircase(proto.staircase, ros_msg.staircase) - ros_msg.staircase_is_set = proto.HasField("staircase") - - -def convert_bosdyn_msgs_staircase_properties_to_proto(ros_msg: "bosdyn_msgs.msgs.StaircaseProperties", proto: "bosdyn.api.world_object_pb2.StaircaseProperties") -> None: - proto.Clear() - if ros_msg.staircase_is_set: - convert_bosdyn_msgs_staircase_to_proto(ros_msg.staircase, proto.staircase) - - -def convert_proto_to_bosdyn_msgs_drawable_frame(proto: "bosdyn.api.world_object_pb2.DrawableFrame", ros_msg: "bosdyn_msgs.msgs.DrawableFrame") -> None: - ros_msg.arrow_length = proto.arrow_length - ros_msg.arrow_radius = proto.arrow_radius - - -def convert_bosdyn_msgs_drawable_frame_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableFrame", proto: "bosdyn.api.world_object_pb2.DrawableFrame") -> None: - proto.Clear() - proto.arrow_length = ros_msg.arrow_length - proto.arrow_radius = ros_msg.arrow_radius - - -def convert_proto_to_bosdyn_msgs_drawable_sphere(proto: "bosdyn.api.world_object_pb2.DrawableSphere", ros_msg: "bosdyn_msgs.msgs.DrawableSphere") -> None: - ros_msg.radius = proto.radius - - -def convert_bosdyn_msgs_drawable_sphere_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableSphere", proto: "bosdyn.api.world_object_pb2.DrawableSphere") -> None: - proto.Clear() - proto.radius = ros_msg.radius - - -def convert_proto_to_bosdyn_msgs_drawable_box(proto: "bosdyn.api.world_object_pb2.DrawableBox", ros_msg: "bosdyn_msgs.msgs.DrawableBox") -> None: - convert_proto_to_geometry_msgs_vector3(proto.size, ros_msg.size) - ros_msg.size_is_set = proto.HasField("size") - - -def convert_bosdyn_msgs_drawable_box_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableBox", proto: "bosdyn.api.world_object_pb2.DrawableBox") -> None: - proto.Clear() - if ros_msg.size_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.size, proto.size) - - -def convert_proto_to_bosdyn_msgs_drawable_arrow(proto: "bosdyn.api.world_object_pb2.DrawableArrow", ros_msg: "bosdyn_msgs.msgs.DrawableArrow") -> None: - convert_proto_to_geometry_msgs_vector3(proto.direction, ros_msg.direction) - ros_msg.direction_is_set = proto.HasField("direction") - ros_msg.radius = proto.radius - - -def convert_bosdyn_msgs_drawable_arrow_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableArrow", proto: "bosdyn.api.world_object_pb2.DrawableArrow") -> None: - proto.Clear() - if ros_msg.direction_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.direction, proto.direction) - proto.radius = ros_msg.radius - - -def convert_proto_to_bosdyn_msgs_drawable_capsule(proto: "bosdyn.api.world_object_pb2.DrawableCapsule", ros_msg: "bosdyn_msgs.msgs.DrawableCapsule") -> None: - convert_proto_to_geometry_msgs_vector3(proto.direction, ros_msg.direction) - ros_msg.direction_is_set = proto.HasField("direction") - ros_msg.radius = proto.radius - - -def convert_bosdyn_msgs_drawable_capsule_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableCapsule", proto: "bosdyn.api.world_object_pb2.DrawableCapsule") -> None: - proto.Clear() - if ros_msg.direction_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.direction, proto.direction) - proto.radius = ros_msg.radius - - -def convert_proto_to_bosdyn_msgs_drawable_cylinder(proto: "bosdyn.api.world_object_pb2.DrawableCylinder", ros_msg: "bosdyn_msgs.msgs.DrawableCylinder") -> None: - convert_proto_to_geometry_msgs_vector3(proto.direction, ros_msg.direction) - ros_msg.direction_is_set = proto.HasField("direction") - ros_msg.radius = proto.radius - - -def convert_bosdyn_msgs_drawable_cylinder_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableCylinder", proto: "bosdyn.api.world_object_pb2.DrawableCylinder") -> None: - proto.Clear() - if ros_msg.direction_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.direction, proto.direction) - proto.radius = ros_msg.radius - - -def convert_proto_to_bosdyn_msgs_drawable_line_strip(proto: "bosdyn.api.world_object_pb2.DrawableLineStrip", ros_msg: "bosdyn_msgs.msgs.DrawableLineStrip") -> None: - convert_proto_to_geometry_msgs_vector3(proto.points, ros_msg.points) - ros_msg.points_is_set = proto.HasField("points") - - -def convert_bosdyn_msgs_drawable_line_strip_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawableLineStrip", proto: "bosdyn.api.world_object_pb2.DrawableLineStrip") -> None: - proto.Clear() - if ros_msg.points_is_set: - convert_geometry_msgs_vector3_to_proto(ros_msg.points, proto.points) - - -def convert_proto_to_bosdyn_msgs_drawable_points(proto: "bosdyn.api.world_object_pb2.DrawablePoints", ros_msg: "bosdyn_msgs.msgs.DrawablePoints") -> None: - from geometry_msgs.msg import Vector3 - ros_msg.points = [] - for _item in proto.points: - ros_msg.points.append(Vector3()) - convert_proto_to_geometry_msgs_vector3(_item, ros_msg.points[-1]) - - -def convert_bosdyn_msgs_drawable_points_to_proto(ros_msg: "bosdyn_msgs.msgs.DrawablePoints", proto: "bosdyn.api.world_object_pb2.DrawablePoints") -> None: - proto.Clear() - del proto.points[:] - for _item in ros_msg.points: - convert_geometry_msgs_vector3_to_proto(_item, proto.points.add()) - -######### AUTOMATICALLY CREATED FILES END HERE ######## diff --git a/spot_driver/spot_driver/ros_helpers.py b/spot_driver/spot_driver/ros_helpers.py index a3eb12401..28ba1e874 100644 --- a/spot_driver/spot_driver/ros_helpers.py +++ b/spot_driver/spot_driver/ros_helpers.py @@ -12,6 +12,7 @@ from bosdyn.api import image_pb2, world_object_pb2 from bosdyn.client.frame_helpers import get_a_tform_b from bosdyn.client.math_helpers import SE3Pose +from bosdyn_api_msgs.math_helpers import ros_transform_to_se3_pose from builtin_interfaces.msg import Time from cv_bridge import CvBridge from geometry_msgs.msg import TransformStamped @@ -22,11 +23,6 @@ from spot_wrapper.wrapper import SpotWrapper -try: - from conversions import ros_transform_to_se3_pose -except ModuleNotFoundError: - from .manual_conversions import ros_transform_to_se3_pose - cv_bridge = CvBridge() diff --git a/spot_driver/spot_driver/spot_ros2.py b/spot_driver/spot_driver/spot_ros2.py index 2ca17f121..0280ee018 100644 --- a/spot_driver/spot_driver/spot_ros2.py +++ b/spot_driver/spot_driver/spot_ros2.py @@ -40,6 +40,8 @@ from bosdyn.client import math_helpers from bosdyn.client.exceptions import InternalServerError from bosdyn.client.lease import LeaseKeepAlive +from bosdyn_api_msgs.math_helpers import bosdyn_localization_to_pose_msg +from bosdyn_msgs.conversions import convert from bosdyn_msgs.msg import ( ArmCommandFeedback, Camera, @@ -74,8 +76,6 @@ from sensor_msgs.msg import CameraInfo, Image from std_srvs.srv import SetBool, Trigger -import spot_driver.conversions as conv - # DEBUG/RELEASE: RELATIVE PATH NOT WORKING IN DEBUG # Release from spot_driver.ros_helpers import ( @@ -1043,7 +1043,7 @@ def publish_graph_nav_pose_callback(self) -> None: ( seed_t_body_msg, seed_t_body_trans_msg, - ) = conv.bosdyn_localization_to_pose_msg( + ) = bosdyn_localization_to_pose_msg( state.localization, self.spot_wrapper.robotToLocalTime, in_seed_frame=True, @@ -1494,7 +1494,7 @@ def handle_list_ptz(self, request: ListPtz.Request, response: ListPtz.Response) descriptions = [] for proto_description in proto_descriptions: ros_msg = PtzDescription() - conv.convert_proto_to_bosdyn_msgs_ptz_description(proto_description, ros_msg) + convert(proto_description, ros_msg) descriptions.append(ros_msg) response.success = True response.message = "Success" @@ -1514,7 +1514,7 @@ def handle_get_ptz_position( raise Exception("Spot CAM has not been initialized") proto_position = self.spot_cam_wrapper.ptz.get_ptz_position(request.name) - conv.convert_proto_to_bosdyn_msgs_ptz_position(proto_position, response.position) + convert(proto_position, response.position) response.success = True response.message = "Success" return response @@ -1567,7 +1567,7 @@ def handle_list_cameras(self, request: ListCameras.Request, response: ListCamera cameras = [] for proto_camera in proto_cameras: ros_msg = Camera() - conv.convert_proto_to_bosdyn_msgs_camera(proto_camera, ros_msg) + convert(proto_camera, ros_msg) cameras.append(ros_msg) response.success = True response.message = "Success" @@ -1590,7 +1590,7 @@ def handle_list_logpoints( logpoints = [] for proto_logpoint in proto_logpoints: ros_msg = Logpoint() - conv.convert_proto_to_bosdyn_msgs_logpoint(proto_logpoint, ros_msg) + convert(proto_logpoint, ros_msg) logpoints.append(ros_msg) response.success = True response.message = "Success" @@ -1612,7 +1612,7 @@ def handle_retrieve_logpoint( proto_logpoint, proto_data_chunk = self.spot_cam_wrapper.media_log.retrieve_logpoint( request.name, request.raw ) - conv.convert_proto_to_bosdyn_msgs_logpoint(proto_logpoint, response.logpoint) + convert(proto_logpoint, response.logpoint) # Data is actually a bytes object, not DataChunk as the SpotCAM wrapper states... # Therefore, we use a uint8[] buffer in srv message and directly set that # to the bytes object. @@ -1671,7 +1671,7 @@ def handle_store_logpoint( tag = None if request.tag == "" else request.tag camera_name = SpotCamCamera(request.name) # Silly but don't want to modify cam wrapper. proto_logpoint = self.spot_cam_wrapper.media_log.store(camera_name, tag) - conv.convert_proto_to_bosdyn_msgs_logpoint(proto_logpoint, response.logpoint) + convert(proto_logpoint, response.logpoint) response.success = True response.message = "Success" return response @@ -1966,7 +1966,7 @@ def _process_synchronized_mobility_command_feedback(self, feedback: MobilityComm elif choice == fb.FEEDBACK_FOLLOW_ARM_FEEDBACK_SET: self.get_logger().warn("WARNING: FollowArmCommand provides no feedback") elif choice == fb.FEEDBACK_NOT_SET: - # sync_feedback.mobility_command_feedback_is_set, feedback_choice is actually not set. + # sync_feedback.mobility_command_feedback is set, but feedback_choice is actually not set. # This may happen when a command finishes, which means we may return SUCCESS below. self.get_logger().info("mobility command feedback indicates goal has reached") else: @@ -2025,19 +2025,19 @@ def _robot_command_goal_complete(self, feedback: RobotCommandFeedback) -> GoalRe # while the mobility is going to some SE2 trajectory then that will work. sync_feedback = feedback.command.synchronized_feedback - if sync_feedback.arm_command_feedback_is_set is True: + if sync_feedback.has_field & sync_feedback.ARM_COMMAND_FEEDBACK_FIELD_SET: arm_feedback = sync_feedback.arm_command_feedback response = self._process_synchronized_arm_command_feedback(arm_feedback) if response is not GoalResponse.SUCCESS: return response - if sync_feedback.mobility_command_feedback_is_set is True: + if sync_feedback.has_field & sync_feedback.MOBILITY_COMMAND_FEEDBACK_FIELD_SET: mob_feedback = sync_feedback.mobility_command_feedback response = self._process_synchronized_mobility_command_feedback(mob_feedback) if response is not GoalResponse.SUCCESS: return response - if sync_feedback.gripper_command_feedback_is_set is True: + if sync_feedback.has_field & sync_feedback.GRIPPER_COMMAND_FEEDBACK_FIELD_SET: grip_feedback = sync_feedback.gripper_command_feedback response = self._process_synchronized_gripper_command_feedback(grip_feedback) if response is not GoalResponse.SUCCESS: @@ -2067,16 +2067,13 @@ def _get_robot_command_feedback(self, goal_id: Optional[str]) -> RobotCommandFee ) else: if self.spot_wrapper is not None: - conv.convert_proto_to_bosdyn_msgs_robot_command_feedback( - self.spot_wrapper.get_robot_command_feedback(goal_id).feedback, - feedback, - ) + convert(self.spot_wrapper.get_robot_command_feedback(goal_id).feedback, feedback) return feedback def handle_robot_command(self, goal_handle: ServerGoalHandle) -> RobotCommand.Result: ros_command = goal_handle.request.command proto_command = robot_command_pb2.RobotCommand() - conv.convert_bosdyn_msgs_robot_command_to_proto(ros_command, proto_command) + convert(ros_command, proto_command) self._wait_for_goal = None if self.spot_wrapper is None: self._wait_for_goal = WaitForGoal(self.get_clock(), 2.0) @@ -2180,9 +2177,7 @@ def _manipulation_goal_complete(self, feedback: Optional[ManipulationApiFeedback def _get_manipulation_command_feedback(self, goal_id: str) -> ManipulationApiFeedbackResponse: feedback = ManipulationApiFeedbackResponse() if self.spot_wrapper is not None: - conv.convert_proto_to_bosdyn_msgs_manipulation_api_feedback_response( - self.spot_wrapper.get_manipulation_command_feedback(goal_id), feedback - ) + convert(self.spot_wrapper.get_manipulation_command_feedback(goal_id), feedback) return feedback def handle_manipulation_command(self, goal_handle: ServerGoalHandle) -> Manipulation.Result: @@ -2191,7 +2186,7 @@ def handle_manipulation_command(self, goal_handle: ServerGoalHandle) -> Manipula ros_command = goal_handle.request.command proto_command = manipulation_api_pb2.ManipulationApiRequest() - conv.convert_bosdyn_msgs_manipulation_api_request_to_proto(ros_command, proto_command) + convert(ros_command, proto_command) self._wait_for_goal = None if not self.spot_wrapper: self._wait_for_goal = WaitForGoal(self.get_clock(), 2.0) @@ -2417,7 +2412,7 @@ def handle_graph_nav_get_localization_pose( self.get_logger().warning(response.message) return response else: - seed_t_body_msg = conv.bosdyn_localization_to_pose_msg( + seed_t_body_msg = bosdyn_localization_to_pose_msg( state.localization, self.spot_wrapper.robotToLocalTime, in_seed_frame=True, @@ -2544,7 +2539,7 @@ def _handle_list_world_objects( ) -> ListWorldObjects.Response: object_types = [ot.value for ot in request.request.object_type] time_start_point = None - if request.request.timestamp_filter_is_set: + if request.request.has_field & request.request.TIMESTAMP_FILTER_FIELD_SET: time_start_point = ( request.request.timestamp_filter.sec + float(request.request.timestamp_filter.nanosec) / 1e9 ) @@ -2559,7 +2554,7 @@ def _handle_list_world_objects( world_object.apriltag_properties.frame_name_fiducial_filtered = "filtered_fiducial_3" else: proto_response = self.spot_wrapper.spot_world_objects.list_world_objects(object_types, time_start_point) - conv.convert_proto_to_bosdyn_msgs_list_world_object_response(proto_response, response.response) + convert(proto_response, response.response) return response def handle_navigate_to_feedback(self) -> None: @@ -2629,9 +2624,9 @@ def handle_get_gripper_camera_parameters( return response try: proto_request = gripper_camera_param_pb2.GripperCameraGetParamRequest() - conv.convert_bosdyn_msgs_gripper_camera_get_param_request_to_proto(request.request, proto_request) + convert(request.request, proto_request) proto_response = self.spot_wrapper.spot_images.get_gripper_camera_params(proto_request) - conv.convert_proto_to_bosdyn_msgs_gripper_camera_get_param_response(proto_response, response.response) + convert(proto_response, response.response) response.success = True response.message = "Request to get gripper camera parameters sent" except Exception as e: @@ -2658,9 +2653,9 @@ def handle_set_gripper_camera_parameters( try: proto_request = gripper_camera_param_pb2.GripperCameraParamRequest() - conv.convert_bosdyn_msgs_gripper_camera_param_request_to_proto(request.request, proto_request) + convert(request.request, proto_request) proto_response = self.spot_wrapper.spot_images.set_gripper_camera_params(proto_request) - conv.convert_proto_to_bosdyn_msgs_gripper_camera_param_response(proto_response, response.response) + convert(proto_response, response.response) response.success = True response.message = "Request to set gripper camera parameters sent" except Exception as e: @@ -2801,7 +2796,6 @@ def destroy_node(self) -> None: self.get_logger().info("Shutting down ROS driver for Spot") if self.spot_wrapper is not None: self.spot_wrapper.sit() - self.node_rate.sleep() if self.spot_wrapper is not None: self.spot_wrapper.disconnect() super().destroy_node() diff --git a/spot_driver/src/conversions/common_conversions.cpp b/spot_driver/src/conversions/common_conversions.cpp index 2c366be9a..ebd8664d1 100644 --- a/spot_driver/src/conversions/common_conversions.cpp +++ b/spot_driver/src/conversions/common_conversions.cpp @@ -12,8 +12,8 @@ void convertToProto(const builtin_interfaces::msg::Time& ros_msg, google::protob proto.set_nanos(ros_msg.nanosec); } -void convertToProto(const bosdyn_msgs::msg::RequestHeader& ros_msg, bosdyn::api::RequestHeader& proto) { - if (ros_msg.request_timestamp_is_set) { +void convertToProto(const bosdyn_api_msgs::msg::RequestHeader& ros_msg, bosdyn::api::RequestHeader& proto) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::RequestHeader::REQUEST_TIMESTAMP_FIELD_SET) { convertToProto(ros_msg.request_timestamp, *proto.mutable_request_timestamp()); } proto.set_client_name(ros_msg.client_name); @@ -44,27 +44,27 @@ void convertToProto(const geometry_msgs::msg::Pose& ros_msg, bosdyn::api::SE3Pos convertToProto(ros_msg.orientation, *proto.mutable_rotation()); } -void convertToProto(const double& ros_msg, google::protobuf::DoubleValue& proto) { - proto.set_value(ros_msg); +void convertToProto(const std_msgs::msg::Float64& ros_msg, google::protobuf::DoubleValue& proto) { + proto.set_value(ros_msg.data); } -void convertToProto(const bosdyn_msgs::msg::ArmJointPosition& ros_msg, bosdyn::api::ArmJointPosition& proto) { - if (ros_msg.sh0_is_set) { +void convertToProto(const bosdyn_api_msgs::msg::ArmJointPosition& ros_msg, bosdyn::api::ArmJointPosition& proto) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::SH0_FIELD_SET) { convertToProto(ros_msg.sh0, *proto.mutable_sh0()); } - if (ros_msg.sh1_is_set) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::SH1_FIELD_SET) { convertToProto(ros_msg.sh1, *proto.mutable_sh1()); } - if (ros_msg.el0_is_set) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::EL0_FIELD_SET) { convertToProto(ros_msg.el0, *proto.mutable_el0()); } - if (ros_msg.el1_is_set) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::EL1_FIELD_SET) { convertToProto(ros_msg.el1, *proto.mutable_el1()); } - if (ros_msg.wr0_is_set) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::WR0_FIELD_SET) { convertToProto(ros_msg.wr0, *proto.mutable_wr0()); } - if (ros_msg.wr1_is_set) { + if (ros_msg.has_field & bosdyn_api_msgs::msg::ArmJointPosition::WR1_FIELD_SET) { convertToProto(ros_msg.wr1, *proto.mutable_wr1()); } } @@ -72,27 +72,39 @@ void convertToProto(const bosdyn_msgs::msg::ArmJointPosition& ros_msg, bosdyn::a /////////////////////////////////////////////////////////////////////////////// // Protobuf to ROS. -void convertToRos(const bosdyn::api::RequestHeader& proto, bosdyn_msgs::msg::RequestHeader& ros_msg) { - convertToRos(proto.request_timestamp(), ros_msg.request_timestamp); - ros_msg.request_timestamp_is_set = proto.has_request_timestamp(); +void convertToRos(const bosdyn::api::RequestHeader& proto, bosdyn_api_msgs::msg::RequestHeader& ros_msg) { + ros_msg.has_field = 0u; + if (proto.has_request_timestamp()) { + convertToRos(proto.request_timestamp(), ros_msg.request_timestamp); + ros_msg.has_field |= bosdyn_api_msgs::msg::RequestHeader::REQUEST_TIMESTAMP_FIELD_SET; + } ros_msg.client_name = proto.client_name(); ros_msg.disable_rpc_logging = proto.disable_rpc_logging(); } -void convertToRos(const bosdyn::api::CommonError& proto, bosdyn_msgs::msg::CommonError& ros_msg) { +void convertToRos(const bosdyn::api::CommonError& proto, bosdyn_api_msgs::msg::CommonError& ros_msg) { ros_msg.code.value = proto.code(); ros_msg.message = proto.message(); } -void convertToRos(const bosdyn::api::ResponseHeader& proto, bosdyn_msgs::msg::ResponseHeader& ros_msg) { - convertToRos(proto.request_header(), ros_msg.request_header); - ros_msg.request_header_is_set = proto.has_request_header(); - convertToRos(proto.request_received_timestamp(), ros_msg.request_received_timestamp); - ros_msg.request_received_timestamp_is_set = proto.has_request_received_timestamp(); - convertToRos(proto.response_timestamp(), ros_msg.response_timestamp); - ros_msg.response_timestamp_is_set = proto.has_response_timestamp(); - convertToRos(proto.error(), ros_msg.error); - ros_msg.error_is_set = proto.has_error(); +void convertToRos(const bosdyn::api::ResponseHeader& proto, bosdyn_api_msgs::msg::ResponseHeader& ros_msg) { + ros_msg.has_field = 0u; + if (proto.has_request_header()) { + convertToRos(proto.request_header(), ros_msg.request_header); + ros_msg.has_field |= bosdyn_api_msgs::msg::ResponseHeader::REQUEST_HEADER_FIELD_SET; + } + if (proto.has_request_received_timestamp()) { + convertToRos(proto.request_received_timestamp(), ros_msg.request_received_timestamp); + ros_msg.has_field |= bosdyn_api_msgs::msg::ResponseHeader::REQUEST_RECEIVED_TIMESTAMP_FIELD_SET; + } + if (proto.has_response_timestamp()) { + convertToRos(proto.response_timestamp(), ros_msg.response_timestamp); + ros_msg.has_field |= bosdyn_api_msgs::msg::ResponseHeader::RESPONSE_TIMESTAMP_FIELD_SET; + } + if (proto.has_error()) { + convertToRos(proto.error(), ros_msg.error); + ros_msg.has_field |= bosdyn_api_msgs::msg::ResponseHeader::ERROR_FIELD_SET; + } } void convertToRos(const google::protobuf::Timestamp& proto, builtin_interfaces::msg::Time& ros_msg) { diff --git a/spot_driver/src/conversions/kinematic_conversions.cpp b/spot_driver/src/conversions/kinematic_conversions.cpp index ac389f7e0..fc40efac3 100644 --- a/spot_driver/src/conversions/kinematic_conversions.cpp +++ b/spot_driver/src/conversions/kinematic_conversions.cpp @@ -9,125 +9,143 @@ namespace spot_ros2 { /////////////////////////////////////////////////////////////////////////////// // ROS to Protobuf. -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestFixedStance& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::FixedStance& proto) { - if (ros_msg.fl_rt_scene_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance::FL_RT_SCENE_FIELD_SET) { convertToProto(ros_msg.fl_rt_scene, *proto.mutable_fl_rt_scene()); } - if (ros_msg.fr_rt_scene_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance::FR_RT_SCENE_FIELD_SET) { convertToProto(ros_msg.fr_rt_scene, *proto.mutable_fr_rt_scene()); } - if (ros_msg.hl_rt_scene_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance::HL_RT_SCENE_FIELD_SET) { convertToProto(ros_msg.hl_rt_scene, *proto.mutable_hl_rt_scene()); } - if (ros_msg.hr_rt_scene_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequestFixedStance::HR_RT_SCENE_FIELD_SET) { convertToProto(ros_msg.hr_rt_scene, *proto.mutable_hr_rt_scene()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOnGroundPlaneStance& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOnGroundPlaneStance& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::OnGroundPlaneStance& proto) { - if (ros_msg.scene_tform_ground_is_set) { + if (ros_msg.has_field & + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOnGroundPlaneStance::SCENE_TFORM_GROUND_FIELD_SET) { convertToProto(ros_msg.scene_tform_ground, *proto.mutable_scene_tform_ground()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto) { - if (ros_msg.stance_specification_choice == - bosdyn_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification::STANCE_SPECIFICATION_FIXED_STANCE_SET) { - convertToProto(ros_msg.fixed_stance, *proto.mutable_fixed_stance()); - } - if (ros_msg.stance_specification_choice == bosdyn_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification:: - STANCE_SPECIFICATION_ON_GROUND_PLANE_STANCE_SET) { - convertToProto(ros_msg.on_ground_plane_stance, *proto.mutable_on_ground_plane_stance()); + switch (ros_msg.which) { + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification:: + STANCE_SPECIFICATION_FIXED_STANCE_SET: + convertToProto(ros_msg.fixed_stance, *proto.mutable_fixed_stance()); + break; + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfStanceSpecification:: + STANCE_SPECIFICATION_ON_GROUND_PLANE_STANCE_SET: + convertToProto(ros_msg.on_ground_plane_stance, *proto.mutable_on_ground_plane_stance()); + break; + default: + break; } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestWristMountedTool& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestWristMountedTool& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::WristMountedTool& proto) { - if (ros_msg.wrist_tform_tool_is_set) { + if (ros_msg.has_field & + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestWristMountedTool::WRIST_TFORM_TOOL_FIELD_SET) { convertToProto(ros_msg.wrist_tform_tool, *proto.mutable_wrist_tform_tool()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestBodyMountedTool& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestBodyMountedTool& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::BodyMountedTool& proto) { - if (ros_msg.body_tform_tool_is_set) { + if (ros_msg.has_field & + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestBodyMountedTool::BODY_TFORM_TOOL_FIELD_SET) { convertToProto(ros_msg.body_tform_tool, *proto.mutable_body_tform_tool()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto) { - if (ros_msg.tool_specification_choice == - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET) { - convertToProto(ros_msg.wrist_mounted_tool, *proto.mutable_wrist_mounted_tool()); - } - if (ros_msg.tool_specification_choice == - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET) { - convertToProto(ros_msg.body_mounted_tool, *proto.mutable_body_mounted_tool()); + switch (ros_msg.which) { + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification:: + TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET: + convertToProto(ros_msg.wrist_mounted_tool, *proto.mutable_wrist_mounted_tool()); + break; + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification:: + TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET: + convertToProto(ros_msg.body_mounted_tool, *proto.mutable_body_mounted_tool()); + break; + default: + break; } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestToolPoseTask& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolPoseTask& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::ToolPoseTask& proto) { - if (ros_msg.task_tform_desired_tool_is_set) { + if (ros_msg.has_field & + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolPoseTask::TASK_TFORM_DESIRED_TOOL_FIELD_SET) { convertToProto(ros_msg.task_tform_desired_tool, *proto.mutable_task_tform_desired_tool()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestToolGazeTask& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolGazeTask& ros_msg, bosdyn::api::spot::InverseKinematicsRequest::ToolGazeTask& proto) { - if (ros_msg.target_in_task_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolGazeTask::TARGET_IN_TASK_FIELD_SET) { convertToProto(ros_msg.target_in_task, *proto.mutable_target_in_task()); } - if (ros_msg.task_tform_desired_tool_is_set) { + if (ros_msg.has_field & + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestToolGazeTask::TASK_TFORM_DESIRED_TOOL_FIELD_SET) { convertToProto(ros_msg.task_tform_desired_tool, *proto.mutable_task_tform_desired_tool()); } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto) { - if (ros_msg.task_specification_choice == - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_POSE_TASK_SET) { - convertToProto(ros_msg.tool_pose_task, *proto.mutable_tool_pose_task()); - } - if (ros_msg.task_specification_choice == - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_GAZE_TASK_SET) { - convertToProto(ros_msg.tool_gaze_task, *proto.mutable_tool_gaze_task()); + switch (ros_msg.which) { + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification:: + TASK_SPECIFICATION_TOOL_POSE_TASK_SET: + convertToProto(ros_msg.tool_pose_task, *proto.mutable_tool_pose_task()); + break; + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification:: + TASK_SPECIFICATION_TOOL_GAZE_TASK_SET: + convertToProto(ros_msg.tool_gaze_task, *proto.mutable_tool_gaze_task()); + break; + default: + break; } } -void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequest& ros_msg, +void convertToProto(const bosdyn_spot_api_msgs::msg::InverseKinematicsRequest& ros_msg, bosdyn::api::spot::InverseKinematicsRequest& proto) { - if (ros_msg.header_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequest::HEADER_FIELD_SET) { convertToProto(ros_msg.header, *proto.mutable_header()); } proto.set_root_frame_name(ros_msg.root_frame_name); - if (ros_msg.root_tform_scene_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequest::ROOT_TFORM_SCENE_FIELD_SET) { convertToProto(ros_msg.root_tform_scene, *proto.mutable_root_tform_scene()); } - if (ros_msg.scene_tform_task_is_set) { + if (ros_msg.has_field & bosdyn_spot_api_msgs::msg::InverseKinematicsRequest::SCENE_TFORM_TASK_FIELD_SET) { convertToProto(ros_msg.scene_tform_task, *proto.mutable_scene_tform_task()); } switch (ros_msg.nominal_arm_configuration.value) { - case bosdyn_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_UNKNOWN: + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_UNKNOWN: proto.set_nominal_arm_configuration(bosdyn::api::spot::InverseKinematicsRequest::ARM_CONFIG_UNKNOWN); break; - case bosdyn_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_READY: + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_READY: proto.set_nominal_arm_configuration(bosdyn::api::spot::InverseKinematicsRequest::ARM_CONFIG_READY); break; - case bosdyn_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_CURRENT: + case bosdyn_spot_api_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_CURRENT: proto.set_nominal_arm_configuration(bosdyn::api::spot::InverseKinematicsRequest::ARM_CONFIG_CURRENT); break; } - if (ros_msg.nominal_arm_configuration_overrides_is_set) { + using InverseKinematicsRequest = bosdyn_spot_api_msgs::msg::InverseKinematicsRequest; + if (ros_msg.has_field & InverseKinematicsRequest::NOMINAL_ARM_CONFIGURATION_OVERRIDES_FIELD_SET) { convertToProto(ros_msg.nominal_arm_configuration_overrides, *proto.mutable_nominal_arm_configuration_overrides()); } - if (ros_msg.scene_tform_body_nominal_is_set) { + if (ros_msg.has_field & InverseKinematicsRequest::SCENE_TFORM_BODY_NOMINAL_FIELD_SET) { convertToProto(ros_msg.scene_tform_body_nominal, *proto.mutable_scene_tform_body_nominal()); } @@ -139,59 +157,85 @@ void convertToProto(const bosdyn_msgs::msg::InverseKinematicsRequest& ros_msg, /////////////////////////////////////////////////////////////////////////////// // Protobuf to ROS. -void convertToRos(const bosdyn::api::JointState& proto, bosdyn_msgs::msg::JointState& ros_msg) { +void convertToRos(const bosdyn::api::JointState& proto, bosdyn_api_msgs::msg::JointState& ros_msg) { + ros_msg.has_field = 0u; ros_msg.name = proto.name(); - ros_msg.position = proto.position().value(); - ros_msg.position_is_set = proto.has_position(); - ros_msg.velocity = proto.velocity().value(); - ros_msg.velocity_is_set = proto.has_velocity(); - ros_msg.acceleration = proto.acceleration().value(); - ros_msg.acceleration_is_set = proto.has_acceleration(); - ros_msg.load = proto.load().value(); - ros_msg.load_is_set = proto.has_load(); + if (proto.has_position()) { + ros_msg.position.data = proto.position().value(); + ros_msg.has_field |= bosdyn_api_msgs::msg::JointState::POSITION_FIELD_SET; + } + if (proto.has_velocity()) { + ros_msg.velocity.data = proto.velocity().value(); + ros_msg.has_field |= bosdyn_api_msgs::msg::JointState::VELOCITY_FIELD_SET; + } + if (proto.has_acceleration()) { + ros_msg.acceleration.data = proto.acceleration().value(); + ros_msg.has_field |= bosdyn_api_msgs::msg::JointState::ACCELERATION_FIELD_SET; + } + if (proto.has_load()) { + ros_msg.load.data = proto.load().value(); + ros_msg.has_field |= bosdyn_api_msgs::msg::JointState::LOAD_FIELD_SET; + } } void convertToRos(const bosdyn::api::FrameTreeSnapshot::ParentEdge& proto, - bosdyn_msgs::msg::FrameTreeSnapshotParentEdge& ros_msg) { + bosdyn_api_msgs::msg::FrameTreeSnapshotParentEdge& ros_msg) { + ros_msg.has_field = 0u; ros_msg.parent_frame_name = proto.parent_frame_name(); - convertToRos(proto.parent_tform_child(), ros_msg.parent_tform_child); - ros_msg.parent_tform_child_is_set = proto.has_parent_tform_child(); + if (proto.has_parent_tform_child()) { + convertToRos(proto.parent_tform_child(), ros_msg.parent_tform_child); + ros_msg.has_field |= bosdyn_api_msgs::msg::FrameTreeSnapshotParentEdge::PARENT_TFORM_CHILD_FIELD_SET; + } } -void convertToRos(const bosdyn::api::FrameTreeSnapshot& proto, bosdyn_msgs::msg::FrameTreeSnapshot& ros_msg) { +void convertToRos(const bosdyn::api::FrameTreeSnapshot& proto, bosdyn_api_msgs::msg::FrameTreeSnapshot& ros_msg) { ros_msg.child_to_parent_edge_map.clear(); for (const auto& item : proto.child_to_parent_edge_map()) { - bosdyn_msgs::msg::KeyStringValueBosdynMsgsFrameTreeSnapshotParentEdge edge; + bosdyn_api_msgs::msg::FrameTreeSnapshotChildToParentEdgeMapEntry edge; edge.key = item.first; convertToRos(item.second, edge.value); ros_msg.child_to_parent_edge_map.push_back(edge); } } -void convertToRos(const bosdyn::api::KinematicState& proto, bosdyn_msgs::msg::KinematicState& ros_msg) { +void convertToRos(const bosdyn::api::KinematicState& proto, bosdyn_api_msgs::msg::KinematicState& ros_msg) { + ros_msg.has_field = 0u; ros_msg.joint_states.clear(); for (const auto& item : proto.joint_states()) { - bosdyn_msgs::msg::JointState joint_state; + bosdyn_api_msgs::msg::JointState joint_state; convertToRos(item, joint_state); ros_msg.joint_states.push_back(joint_state); } - convertToRos(proto.acquisition_timestamp(), ros_msg.acquisition_timestamp); - ros_msg.acquisition_timestamp_is_set = proto.has_acquisition_timestamp(); - convertToRos(proto.transforms_snapshot(), ros_msg.transforms_snapshot); - ros_msg.transforms_snapshot_is_set = proto.has_transforms_snapshot(); - convertToRos(proto.velocity_of_body_in_vision(), ros_msg.velocity_of_body_in_vision); - ros_msg.velocity_of_body_in_vision_is_set = proto.has_velocity_of_body_in_vision(); - convertToRos(proto.velocity_of_body_in_odom(), ros_msg.velocity_of_body_in_odom); - ros_msg.velocity_of_body_in_odom_is_set = proto.has_velocity_of_body_in_odom(); + if (proto.has_acquisition_timestamp()) { + convertToRos(proto.acquisition_timestamp(), ros_msg.acquisition_timestamp); + ros_msg.has_field |= bosdyn_api_msgs::msg::KinematicState::ACQUISITION_TIMESTAMP_FIELD_SET; + } + if (proto.has_transforms_snapshot()) { + convertToRos(proto.transforms_snapshot(), ros_msg.transforms_snapshot); + ros_msg.has_field |= bosdyn_api_msgs::msg::KinematicState::TRANSFORMS_SNAPSHOT_FIELD_SET; + } + if (proto.has_velocity_of_body_in_vision()) { + convertToRos(proto.velocity_of_body_in_vision(), ros_msg.velocity_of_body_in_vision); + ros_msg.has_field |= bosdyn_api_msgs::msg::KinematicState::VELOCITY_OF_BODY_IN_VISION_FIELD_SET; + } + if (proto.has_velocity_of_body_in_odom()) { + convertToRos(proto.velocity_of_body_in_odom(), ros_msg.velocity_of_body_in_odom); + ros_msg.has_field |= bosdyn_api_msgs::msg::KinematicState::VELOCITY_OF_BODY_IN_ODOM_FIELD_SET; + } } void convertToRos(const bosdyn::api::spot::InverseKinematicsResponse& proto, - bosdyn_msgs::msg::InverseKinematicsResponse& ros_msg) { - convertToRos(proto.header(), ros_msg.header); - ros_msg.header_is_set = proto.has_header(); + bosdyn_spot_api_msgs::msg::InverseKinematicsResponse& ros_msg) { + ros_msg.has_field = 0u; + if (proto.has_header()) { + convertToRos(proto.header(), ros_msg.header); + ros_msg.has_field |= bosdyn_spot_api_msgs::msg::InverseKinematicsResponse::HEADER_FIELD_SET; + } ros_msg.status.value = proto.status(); - convertToRos(proto.robot_configuration(), ros_msg.robot_configuration); - ros_msg.robot_configuration_is_set = proto.has_robot_configuration(); + if (proto.has_robot_configuration()) { + convertToRos(proto.robot_configuration(), ros_msg.robot_configuration); + ros_msg.has_field |= bosdyn_spot_api_msgs::msg::InverseKinematicsResponse::ROBOT_CONFIGURATION_FIELD_SET; + } } } // namespace spot_ros2 diff --git a/spot_driver/src/conversions/robot_state.cpp b/spot_driver/src/conversions/robot_state.cpp index 886c7b6ba..cd3cce299 100644 --- a/spot_driver/src/conversions/robot_state.cpp +++ b/spot_driver/src/conversions/robot_state.cpp @@ -239,30 +239,39 @@ std::optional getSystemFaultState(const ::bosd return system_fault_state; } -std::optional getManipulatorState(const ::bosdyn::api::RobotState& robot_state) { +std::optional getManipulatorState( + const ::bosdyn::api::RobotState& robot_state) { + using ManipulatorState = bosdyn_api_msgs::msg::ManipulatorState; + if (!robot_state.has_manipulator_state()) { return std::nullopt; } const auto& manipulator_state = robot_state.manipulator_state(); - bosdyn_msgs::msg::ManipulatorState manipulator_state_msg; + ManipulatorState manipulator_state_msg; + manipulator_state_msg.has_field = 0u; manipulator_state_msg.gripper_open_percentage = manipulator_state.gripper_open_percentage(); manipulator_state_msg.is_gripper_holding_item = manipulator_state.is_gripper_holding_item(); - convertToRos(manipulator_state.estimated_end_effector_force_in_hand(), - manipulator_state_msg.estimated_end_effector_force_in_hand); - manipulator_state_msg.estimated_end_effector_force_in_hand_is_set = - manipulator_state.has_estimated_end_effector_force_in_hand(); + if (manipulator_state.has_estimated_end_effector_force_in_hand()) { + convertToRos(manipulator_state.estimated_end_effector_force_in_hand(), + manipulator_state_msg.estimated_end_effector_force_in_hand); + manipulator_state_msg.has_field |= ManipulatorState::ESTIMATED_END_EFFECTOR_FORCE_IN_HAND_FIELD_SET; + } manipulator_state_msg.stow_state.value = manipulator_state.stow_state(); - convertToRos(manipulator_state.velocity_of_hand_in_vision(), manipulator_state_msg.velocity_of_hand_in_vision); - manipulator_state_msg.velocity_of_hand_in_vision_is_set = manipulator_state.has_velocity_of_hand_in_vision(); + if (manipulator_state.has_velocity_of_hand_in_vision()) { + convertToRos(manipulator_state.velocity_of_hand_in_vision(), manipulator_state_msg.velocity_of_hand_in_vision); + manipulator_state_msg.has_field |= ManipulatorState::VELOCITY_OF_HAND_IN_VISION_FIELD_SET; + } - convertToRos(manipulator_state.velocity_of_hand_in_odom(), manipulator_state_msg.velocity_of_hand_in_odom); - manipulator_state_msg.velocity_of_hand_in_odom_is_set = manipulator_state.has_velocity_of_hand_in_odom(); + if (manipulator_state.has_velocity_of_hand_in_odom()) { + convertToRos(manipulator_state.velocity_of_hand_in_odom(), manipulator_state_msg.velocity_of_hand_in_odom); + manipulator_state_msg.has_field |= ManipulatorState::VELOCITY_OF_HAND_IN_ODOM_FIELD_SET; + } manipulator_state_msg.carry_state.value = manipulator_state.carry_state(); return manipulator_state_msg; diff --git a/spot_driver/src/kinematic/kinematic_service.cpp b/spot_driver/src/kinematic/kinematic_service.cpp index b5427ca04..25e064e9f 100644 --- a/spot_driver/src/kinematic/kinematic_service.cpp +++ b/spot_driver/src/kinematic/kinematic_service.cpp @@ -34,7 +34,7 @@ void KinematicService::getSolutions(const std::shared_ptrgetSolutions(proto_request); if (!expected) { logger_->logError(std::string{"Error querying the Inverse Kinematics service: "}.append(expected.error())); - response->response.status.value = bosdyn_msgs::msg::InverseKinematicsResponseStatus::STATUS_UNKNOWN; + response->response.status.value = bosdyn_spot_api_msgs::msg::InverseKinematicsResponseStatus::STATUS_UNKNOWN; } else { convertToRos(expected.value(), response->response); } diff --git a/spot_driver/src/robot_state/state_middleware_handle.cpp b/spot_driver/src/robot_state/state_middleware_handle.cpp index 7121d3b04..4ec6ad11b 100644 --- a/spot_driver/src/robot_state/state_middleware_handle.cpp +++ b/spot_driver/src/robot_state/state_middleware_handle.cpp @@ -56,7 +56,7 @@ StateMiddlewareHandle::StateMiddlewareHandle(const std::shared_ptr system_faults_publisher_{ node_->create_publisher(kSystemFaultsTopic, makeQoS())}, manipulator_state_publisher_{ - node_->create_publisher(kManipulatorTopic, makeQoS())}, + node_->create_publisher(kManipulatorTopic, makeQoS())}, end_effector_force_publisher_{ node_->create_publisher(kEndEffectorForceTopic, makeQoS())}, behavior_fault_state_publisher_{ diff --git a/spot_driver/test/include/spot_driver/matchers.hpp b/spot_driver/test/include/spot_driver/matchers.hpp index 2a463a8f9..c2b235526 100644 --- a/spot_driver/test/include/spot_driver/matchers.hpp +++ b/spot_driver/test/include/spot_driver/matchers.hpp @@ -106,9 +106,9 @@ MATCHER_P6(EStopStatesContains, name, type, state, state_description, timestamp, MATCHER_P(DurationEq, duration, "") { return testing::ExplainMatchResult( - testing::AllOf( - testing::Field("sec", &builtin_interfaces::msg::Duration::sec, testing::Eq(duration.seconds())), - testing::Field("nanosec", &builtin_interfaces::msg::Duration::nanosec, testing::Eq(duration.nanos()))), + testing::AllOf(testing::Field("sec", &builtin_interfaces::msg::Duration::sec, testing::Eq(duration.seconds())), + testing::Field("nanosec", &builtin_interfaces::msg::Duration::nanosec, + testing::Eq(static_cast(duration.nanos())))), arg, result_listener); } @@ -123,4 +123,8 @@ MATCHER_P8(SystemFaultEq, timestamp, clock_skew, duration, name, uid, code, erro testing::Field("attributes", &SystemFault::attributes, testing::ContainerEq(attributes))), arg, result_listener); } + +MATCHER_P(HasEnabledBit, mask, "") { + return (arg & mask) != 0; +} } // namespace spot_ros2::test diff --git a/spot_driver/test/include/spot_driver/robot_state_test_tools.hpp b/spot_driver/test/include/spot_driver/robot_state_test_tools.hpp index f7348564f..9ae03edb7 100644 --- a/spot_driver/test/include/spot_driver/robot_state_test_tools.hpp +++ b/spot_driver/test/include/spot_driver/robot_state_test_tools.hpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/spot_driver/test/pytests/test_dock.py b/spot_driver/test/pytests/test_dock.py index 854f4ef32..0ad9eeb7d 100644 --- a/spot_driver/test/pytests/test_dock.py +++ b/spot_driver/test/pytests/test_dock.py @@ -20,7 +20,7 @@ @pytest.mark.usefixtures("spot_node") -def test_dock(ros: ROSAwareScope, simple_spot: SpotFixture) -> None: +def test_dock(simple_spot: SpotFixture, ros: ROSAwareScope) -> None: """ This integration test checks if the "undock" service infrastructure is setup correctly. @@ -59,7 +59,6 @@ def test_dock(ros: ROSAwareScope, simple_spot: SpotFixture) -> None: stand_feedback_response.feedback.synchronized_feedback.mobility_command_feedback.status = ( RobotCommandFeedbackStatus.STATUS_PROCESSING ) - stand_feedback_response.status = RobotCommandResponse.Status.STATUS_OK stand_feedback_call.returns(stand_feedback_response) # Serve dock command. @@ -158,7 +157,6 @@ def test_dock_with_dock_command_failed(ros: ROSAwareScope, simple_spot: SpotFixt stand_feedback_response.feedback.synchronized_feedback.mobility_command_feedback.status = ( RobotCommandFeedbackStatus.STATUS_PROCESSING ) - stand_feedback_response.status = RobotCommandResponse.Status.STATUS_OK stand_feedback_call.returns(stand_feedback_response) # Serve dock command and return unknown error. diff --git a/spot_driver/test/pytests/test_robot_command.py b/spot_driver/test/pytests/test_robot_command.py index 2f33bbc93..738656211 100644 --- a/spot_driver/test/pytests/test_robot_command.py +++ b/spot_driver/test/pytests/test_robot_command.py @@ -62,7 +62,6 @@ def test_robot_command(ros: ROSAwareScope, simple_spot: SpotFixture) -> None: ) ) ) - feedback_response.status = RobotCommandResponse.Status.STATUS_OK feedback_call.returns(feedback_response) # Query and wait for the action result. diff --git a/spot_driver/test/pytests/test_ros_interfaces.py b/spot_driver/test/pytests/test_ros_interfaces.py index 885ef1dbe..ea1e92d69 100644 --- a/spot_driver/test/pytests/test_ros_interfaces.py +++ b/spot_driver/test/pytests/test_ros_interfaces.py @@ -310,9 +310,9 @@ def test_robot_command_goal_complete(self) -> None: feedback.command.command_choice = feedback.command.COMMAND_SYNCHRONIZED_FEEDBACK_SET """ Testing arm command feedback """ - feedback.command.synchronized_feedback.arm_command_feedback_is_set = True - feedback.command.synchronized_feedback.mobility_command_feedback_is_set = False - feedback.command.synchronized_feedback.gripper_command_feedback_is_set = False + feedback.command.synchronized_feedback.has_field = ( + feedback.command.synchronized_feedback.ARM_COMMAND_FEEDBACK_FIELD_SET + ) feedback.command.synchronized_feedback.arm_command_feedback.status.value = ( arm_command_feedback.status.STATUS_COMMAND_OVERRIDDEN @@ -641,9 +641,9 @@ def test_robot_command_goal_complete(self) -> None: """ Testing mobility commands """ mobility_feedback = RobotCommandFeedback().command.synchronized_feedback.mobility_command_feedback - feedback.command.synchronized_feedback.arm_command_feedback_is_set = False - feedback.command.synchronized_feedback.mobility_command_feedback_is_set = True - feedback.command.synchronized_feedback.gripper_command_feedback_is_set = False + feedback.command.synchronized_feedback.has_field = ( + feedback.command.synchronized_feedback.MOBILITY_COMMAND_FEEDBACK_FIELD_SET + ) feedback.command.synchronized_feedback.mobility_command_feedback.status.value = ( mobility_feedback.status.STATUS_COMMAND_OVERRIDDEN @@ -883,9 +883,9 @@ def test_robot_command_goal_complete(self) -> None: """ Testing Gripper commands """ gripper_feedback = RobotCommandFeedback().command.synchronized_feedback.gripper_command_feedback - feedback.command.synchronized_feedback.arm_command_feedback_is_set = False - feedback.command.synchronized_feedback.mobility_command_feedback_is_set = False - feedback.command.synchronized_feedback.gripper_command_feedback_is_set = True + feedback.command.synchronized_feedback.has_field = ( + feedback.command.synchronized_feedback.GRIPPER_COMMAND_FEEDBACK_FIELD_SET + ) feedback.command.synchronized_feedback.gripper_command_feedback.status.value = ( gripper_feedback.status.STATUS_COMMAND_OVERRIDDEN diff --git a/spot_driver/test/src/conversions/test_common_conversions.cpp b/spot_driver/test/src/conversions/test_common_conversions.cpp index ceb1f69ca..03702d4e2 100644 --- a/spot_driver/test/src/conversions/test_common_conversions.cpp +++ b/spot_driver/test/src/conversions/test_common_conversions.cpp @@ -5,14 +5,13 @@ #include #include #include -#include -#include +#include #include #include namespace { -using ArmJointPosition = bosdyn_msgs::msg::ArmJointPosition; +using ArmJointPosition = bosdyn_api_msgs::msg::ArmJointPosition; } namespace spot_ros2::test { @@ -30,7 +29,7 @@ TEST(TestCommonConversions, convert_builtin_interfaces_time_to_proto) { convertToProto(rosMsg, protoMsg); ASSERT_EQ(rosMsg.sec, protoMsg.seconds()); - ASSERT_EQ(rosMsg.nanosec, protoMsg.nanos()); + ASSERT_EQ(static_cast(rosMsg.nanosec), protoMsg.nanos()); } TEST(TestCommonConversions, convertGeometryMsgsVector3ToProto) { @@ -81,18 +80,18 @@ TEST(TestCommonConversions, convertGeometryMsgsQuaternionToProto) { } TEST(TestCommonConversions, convertBosdynMsgsRequestHeaderToProto) { - bosdyn_msgs::msg::RequestHeader rosMsg; + bosdyn_api_msgs::msg::RequestHeader rosMsg; bosdyn::api::RequestHeader protoMsg; - rosMsg.request_timestamp_is_set = true; + // All fields set by default. rosMsg.client_name = "client_name"; rosMsg.disable_rpc_logging = true; convertToProto(rosMsg, protoMsg); - ASSERT_EQ(rosMsg.request_timestamp_is_set, protoMsg.has_request_timestamp()); - ASSERT_EQ(rosMsg.client_name = "client_name", protoMsg.client_name()); - ASSERT_EQ(rosMsg.disable_rpc_logging = true, protoMsg.disable_rpc_logging()); + ASSERT_TRUE(protoMsg.has_request_timestamp()); + ASSERT_EQ(rosMsg.client_name, protoMsg.client_name()); + ASSERT_EQ(rosMsg.disable_rpc_logging, protoMsg.disable_rpc_logging()); } class ConvertBosdynMsgsArmJointPositionToProtoParameterized : public ::testing::TestWithParam {}; @@ -105,129 +104,65 @@ TEST_P(ConvertBosdynMsgsArmJointPositionToProtoParameterized, CheckFieldsNotSet) convertToProto(ros_msg, proto_msg); // THEN we expect that each corresponding field is set and has the same value - EXPECT_THAT(proto_msg.has_sh0(), testing::Eq(ros_msg.sh0_is_set)); - if (ros_msg.sh0_is_set) { - EXPECT_THAT(proto_msg.sh0().value(), testing::DoubleEq(ros_msg.sh0)); + const bool sh0_is_set = (ros_msg.has_field & ArmJointPosition::SH0_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_sh0(), testing::Eq(sh0_is_set)); + if (sh0_is_set) { + EXPECT_THAT(proto_msg.sh0().value(), testing::DoubleEq(ros_msg.sh0.data)); } - EXPECT_THAT(proto_msg.has_sh1(), testing::Eq(ros_msg.sh1_is_set)); - if (ros_msg.sh1_is_set) { - EXPECT_THAT(proto_msg.sh1().value(), testing::DoubleEq(ros_msg.sh1)); + const bool sh1_is_set = (ros_msg.has_field & ArmJointPosition::SH1_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_sh1(), testing::Eq(sh1_is_set)); + if (sh1_is_set) { + EXPECT_THAT(proto_msg.sh1().value(), testing::DoubleEq(ros_msg.sh1.data)); } - EXPECT_THAT(proto_msg.has_el0(), testing::Eq(ros_msg.el0_is_set)); - if (ros_msg.el0_is_set) { - EXPECT_THAT(proto_msg.el0().value(), testing::DoubleEq(ros_msg.el0)); + const bool el0_is_set = (ros_msg.has_field & ArmJointPosition::EL0_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_el0(), testing::Eq(el0_is_set)); + if (el0_is_set) { + EXPECT_THAT(proto_msg.el0().value(), testing::DoubleEq(ros_msg.el0.data)); } - EXPECT_THAT(proto_msg.has_el1(), testing::Eq(ros_msg.el1_is_set)); - if (ros_msg.el1_is_set) { - EXPECT_THAT(proto_msg.el1().value(), testing::DoubleEq(ros_msg.el1)); + const bool el1_is_set = (ros_msg.has_field & ArmJointPosition::EL1_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_el1(), testing::Eq(el1_is_set)); + if (el1_is_set) { + EXPECT_THAT(proto_msg.el1().value(), testing::DoubleEq(ros_msg.el1.data)); } - EXPECT_THAT(proto_msg.has_wr0(), testing::Eq(ros_msg.wr0_is_set)); - if (ros_msg.wr0_is_set) { - EXPECT_THAT(proto_msg.wr0().value(), testing::DoubleEq(ros_msg.wr0)); + const bool wr0_is_set = (ros_msg.has_field & ArmJointPosition::WR0_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_wr0(), testing::Eq(wr0_is_set)); + if (wr0_is_set) { + EXPECT_THAT(proto_msg.wr0().value(), testing::DoubleEq(ros_msg.wr0.data)); } - EXPECT_THAT(proto_msg.has_wr1(), testing::Eq(ros_msg.wr1_is_set)); - if (ros_msg.wr1_is_set) { - EXPECT_THAT(proto_msg.wr1().value(), testing::DoubleEq(ros_msg.wr1)); + const bool wr1_is_set = (ros_msg.has_field & ArmJointPosition::WR1_FIELD_SET) != 0; + EXPECT_THAT(proto_msg.has_wr1(), testing::Eq(wr1_is_set)); + if (wr1_is_set) { + EXPECT_THAT(proto_msg.wr1().value(), testing::DoubleEq(ros_msg.wr1.data)); } } -INSTANTIATE_TEST_CASE_P(ConvertBosdynMsgsArmJointPositionToProto, ConvertBosdynMsgsArmJointPositionToProtoParameterized, - ::testing::Values(bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.3) - .el0_is_set(true) - .el1(0.4) - .el1_is_set(true) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.0) - .sh0_is_set(false) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.3) - .el0_is_set(true) - .el1(0.4) - .el1_is_set(true) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.0) - .sh1_is_set(false) - .el0(0.3) - .el0_is_set(true) - .el1(0.4) - .el1_is_set(true) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.0) - .el0_is_set(false) - .el1(0.4) - .el1_is_set(true) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.3) - .el0_is_set(true) - .el1(0.0) - .el1_is_set(false) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.3) - .el0_is_set(true) - .el1(0.4) - .el1_is_set(true) - .wr0(0.0) - .wr0_is_set(false) - .wr1(0.6) - .wr1_is_set(true), - bosdyn_msgs::build() - .sh0(0.1) - .sh0_is_set(true) - .sh1(0.2) - .sh1_is_set(true) - .el0(0.3) - .el0_is_set(true) - .el1(0.4) - .el1_is_set(true) - .wr0(0.5) - .wr0_is_set(true) - .wr1(0.0) - .wr1_is_set(false))); +std::vector BuildArmJointPositionsForTesting() { + ArmJointPosition default_arm_joint_position; + default_arm_joint_position.sh0.data = 0.1; + default_arm_joint_position.sh1.data = 0.2; + default_arm_joint_position.el0.data = 0.3; + default_arm_joint_position.el1.data = 0.4; + default_arm_joint_position.wr0.data = 0.5; + default_arm_joint_position.wr1.data = 0.6; + + std::vector values(7, default_arm_joint_position); + values[1].has_field &= ~ArmJointPosition::SH0_FIELD_SET; + values[2].has_field &= ~ArmJointPosition::SH1_FIELD_SET; + values[3].has_field &= ~ArmJointPosition::EL0_FIELD_SET; + values[4].has_field &= ~ArmJointPosition::EL1_FIELD_SET; + values[5].has_field &= ~ArmJointPosition::WR0_FIELD_SET; + values[6].has_field &= ~ArmJointPosition::WR1_FIELD_SET; + return values; +} + +INSTANTIATE_TEST_SUITE_P(ConvertBosdynMsgsArmJointPositionToProto, + ConvertBosdynMsgsArmJointPositionToProtoParameterized, + ::testing::ValuesIn(BuildArmJointPositionsForTesting())); /////////////////////////////////////////////////////////////////////////////// // Protobuf to ROS. @@ -242,7 +177,7 @@ TEST(TestCommonConversions, convertProtoToBuiltinInterfacesTime) { convertToRos(protoMsg, rosMsg); ASSERT_EQ(protoMsg.seconds(), rosMsg.sec); - ASSERT_EQ(protoMsg.nanos(), rosMsg.nanosec); + ASSERT_EQ(protoMsg.nanos(), static_cast(rosMsg.nanosec)); } TEST(TestCommonConversions, convertProtoToGeometryMsgsVector3) { @@ -277,4 +212,43 @@ TEST(TestCommonConversions, convertProtoToGeometryMsgsQuaternion) { ASSERT_EQ(protoMsg.z(), rosMsg.z); } +TEST(TestCommonConversions, convertProtoToBosdynMsgsRequestHeader) { + bosdyn::api::RequestHeader protoMsg; + bosdyn_api_msgs::msg::RequestHeader rosMsg; + + protoMsg.mutable_request_timestamp()->set_seconds(1); + protoMsg.set_client_name("client_name"); + protoMsg.set_disable_rpc_logging(true); + + convertToRos(protoMsg, rosMsg); + + ASSERT_TRUE(rosMsg.has_field & bosdyn_api_msgs::msg::RequestHeader::REQUEST_TIMESTAMP_FIELD_SET); + ASSERT_EQ(protoMsg.request_timestamp().seconds(), rosMsg.request_timestamp.sec); + ASSERT_EQ(protoMsg.client_name(), rosMsg.client_name); + ASSERT_EQ(protoMsg.disable_rpc_logging(), rosMsg.disable_rpc_logging); +} + +TEST(TestCommonConversions, convertProtoToBosdynMsgsResponseHeader) { + bosdyn::api::ResponseHeader protoMsg; + bosdyn_api_msgs::msg::ResponseHeader rosMsg; + + protoMsg.mutable_request_header()->set_client_name("client_name"); + protoMsg.mutable_request_received_timestamp()->set_seconds(1); + protoMsg.mutable_response_timestamp()->set_seconds(2); + protoMsg.mutable_error()->set_message("ok"); + + convertToRos(protoMsg, rosMsg); + + using ResponseHeader = bosdyn_api_msgs::msg::ResponseHeader; + ASSERT_TRUE(rosMsg.has_field & ResponseHeader::REQUEST_HEADER_FIELD_SET); + ASSERT_TRUE(rosMsg.has_field & ResponseHeader::REQUEST_RECEIVED_TIMESTAMP_FIELD_SET); + ASSERT_TRUE(rosMsg.has_field & ResponseHeader::RESPONSE_TIMESTAMP_FIELD_SET); + ASSERT_TRUE(rosMsg.has_field & ResponseHeader::ERROR_FIELD_SET); + + ASSERT_EQ(protoMsg.request_header().client_name(), rosMsg.request_header.client_name); + ASSERT_EQ(protoMsg.request_received_timestamp().seconds(), rosMsg.request_received_timestamp.sec); + ASSERT_EQ(protoMsg.response_timestamp().seconds(), rosMsg.response_timestamp.sec); + ASSERT_EQ(protoMsg.error().message(), rosMsg.error.message); +} + } // namespace spot_ros2::test diff --git a/spot_driver/test/src/conversions/test_kinematic_conversions.cpp b/spot_driver/test/src/conversions/test_kinematic_conversions.cpp index 4574f0569..454655b0e 100644 --- a/spot_driver/test/src/conversions/test_kinematic_conversions.cpp +++ b/spot_driver/test/src/conversions/test_kinematic_conversions.cpp @@ -11,81 +11,74 @@ namespace spot_ros2::test { // ROS to Protobuf. TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestToProto) { - bosdyn_msgs::msg::InverseKinematicsRequest rosMsg; + bosdyn_spot_api_msgs::msg::InverseKinematicsRequest rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.header_is_set = true; + // All fields assumed set by default. rosMsg.root_frame_name = "root_frame_name"; - rosMsg.root_tform_scene_is_set = true; - rosMsg.scene_tform_task_is_set = true; rosMsg.nominal_arm_configuration.value = - bosdyn_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_READY; - rosMsg.nominal_arm_configuration_overrides_is_set = true; - rosMsg.scene_tform_body_nominal_is_set = true; + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestNamedArmConfiguration::ARM_CONFIG_READY; convertToProto(rosMsg, protoMsg); - ASSERT_EQ(rosMsg.header_is_set, protoMsg.has_header()); + ASSERT_TRUE(protoMsg.has_header()); ASSERT_EQ(rosMsg.root_frame_name, protoMsg.root_frame_name()); - ASSERT_EQ(rosMsg.root_tform_scene_is_set, protoMsg.has_root_tform_scene()); - ASSERT_EQ(rosMsg.scene_tform_task_is_set, protoMsg.has_scene_tform_task()); + ASSERT_TRUE(protoMsg.has_root_tform_scene()); + ASSERT_TRUE(protoMsg.has_scene_tform_task()); ASSERT_EQ(rosMsg.nominal_arm_configuration.value, protoMsg.nominal_arm_configuration()); - ASSERT_EQ(rosMsg.nominal_arm_configuration_overrides_is_set, protoMsg.has_nominal_arm_configuration_overrides()); - ASSERT_EQ(rosMsg.scene_tform_body_nominal_is_set, protoMsg.has_scene_tform_body_nominal()); + ASSERT_TRUE(protoMsg.has_nominal_arm_configuration_overrides()); + ASSERT_TRUE(protoMsg.has_scene_tform_body_nominal()); } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestFixedStanceToProto) { - bosdyn_msgs::msg::InverseKinematicsRequest rosMsg; + bosdyn_spot_api_msgs::msg::InverseKinematicsRequest rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.stance_specification.fixed_stance.fl_rt_scene_is_set = true; + // All fields assumed set by default. rosMsg.stance_specification.fixed_stance.fl_rt_scene.x = 0.1; rosMsg.stance_specification.fixed_stance.fl_rt_scene.y = 0.2; rosMsg.stance_specification.fixed_stance.fl_rt_scene.z = 0.3; - rosMsg.stance_specification.fixed_stance.fr_rt_scene_is_set = true; rosMsg.stance_specification.fixed_stance.fr_rt_scene.x = 0.1; rosMsg.stance_specification.fixed_stance.fr_rt_scene.y = 0.2; rosMsg.stance_specification.fixed_stance.fr_rt_scene.z = 0.3; - rosMsg.stance_specification.fixed_stance.hl_rt_scene_is_set = true; rosMsg.stance_specification.fixed_stance.hl_rt_scene.x = 0.1; rosMsg.stance_specification.fixed_stance.hl_rt_scene.y = 0.2; rosMsg.stance_specification.fixed_stance.hl_rt_scene.z = 0.3; - rosMsg.stance_specification.fixed_stance.hr_rt_scene_is_set = true; rosMsg.stance_specification.fixed_stance.hr_rt_scene.x = 0.1; rosMsg.stance_specification.fixed_stance.hr_rt_scene.y = 0.2; rosMsg.stance_specification.fixed_stance.hr_rt_scene.z = 0.3; convertToProto(rosMsg.stance_specification.fixed_stance, *protoMsg.mutable_fixed_stance()); - ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fl_rt_scene_is_set, protoMsg.fixed_stance().has_fl_rt_scene()); + ASSERT_TRUE(protoMsg.fixed_stance().has_fl_rt_scene()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fl_rt_scene.x, protoMsg.fixed_stance().fl_rt_scene().x()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fl_rt_scene.y, protoMsg.fixed_stance().fl_rt_scene().y()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fl_rt_scene.z, protoMsg.fixed_stance().fl_rt_scene().z()); - ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fr_rt_scene_is_set, protoMsg.fixed_stance().has_fr_rt_scene()); + ASSERT_TRUE(protoMsg.fixed_stance().has_fr_rt_scene()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fr_rt_scene.x, protoMsg.fixed_stance().fr_rt_scene().x()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fr_rt_scene.y, protoMsg.fixed_stance().fr_rt_scene().y()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.fr_rt_scene.z, protoMsg.fixed_stance().fr_rt_scene().z()); - ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hl_rt_scene_is_set, protoMsg.fixed_stance().has_hl_rt_scene()); + ASSERT_TRUE(protoMsg.fixed_stance().has_hl_rt_scene()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hl_rt_scene.x, protoMsg.fixed_stance().hl_rt_scene().x()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hl_rt_scene.y, protoMsg.fixed_stance().hl_rt_scene().y()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hl_rt_scene.z, protoMsg.fixed_stance().hl_rt_scene().z()); - ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hr_rt_scene_is_set, protoMsg.fixed_stance().has_hr_rt_scene()); + ASSERT_TRUE(protoMsg.fixed_stance().has_hr_rt_scene()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hr_rt_scene.x, protoMsg.fixed_stance().hr_rt_scene().x()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hr_rt_scene.y, protoMsg.fixed_stance().hr_rt_scene().y()); ASSERT_EQ(rosMsg.stance_specification.fixed_stance.hr_rt_scene.z, protoMsg.fixed_stance().hr_rt_scene().z()); } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOnGroundPlaneStanceToProto) { - bosdyn_msgs::msg::InverseKinematicsRequest rosMsg; + bosdyn_spot_api_msgs::msg::InverseKinematicsRequest rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground_is_set = true; + // Field assumed set by default. rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground.position.x = 0.1; rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground.position.y = 0.2; rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground.position.z = 0.3; @@ -96,8 +89,7 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOnGround convertToProto(rosMsg.stance_specification.on_ground_plane_stance, *protoMsg.mutable_on_ground_plane_stance()); - ASSERT_EQ(rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground_is_set, - protoMsg.on_ground_plane_stance().has_scene_tform_ground()); + ASSERT_TRUE(protoMsg.on_ground_plane_stance().has_scene_tform_ground()); ASSERT_EQ(rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground.position.x, protoMsg.on_ground_plane_stance().scene_tform_ground().position().x()); ASSERT_EQ(rosMsg.stance_specification.on_ground_plane_stance.scene_tform_ground.position.y, @@ -115,12 +107,12 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOnGround } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfToolSpecificationToProtoWristMounted) { - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification rosMsg; + using InverseKinematicsRequestOneOfToolSpecification = + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification; + InverseKinematicsRequestOneOfToolSpecification rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.wrist_mounted_tool.wrist_tform_tool_is_set = true; - rosMsg.tool_specification_choice = - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET; + rosMsg.which = InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_WRIST_MOUNTED_TOOL_SET; rosMsg.wrist_mounted_tool.wrist_tform_tool.position.x = 0.1; rosMsg.wrist_mounted_tool.wrist_tform_tool.position.y = 0.2; rosMsg.wrist_mounted_tool.wrist_tform_tool.position.z = 0.3; @@ -147,12 +139,13 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfToo } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfToolSpecificationToProtoBodyMounted) { - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification rosMsg; + using InverseKinematicsRequestOneOfToolSpecification = + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfToolSpecification; + InverseKinematicsRequestOneOfToolSpecification rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.body_mounted_tool.body_tform_tool_is_set = true; - rosMsg.tool_specification_choice = - bosdyn_msgs::msg::InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET; + rosMsg.which = InverseKinematicsRequestOneOfToolSpecification::TOOL_SPECIFICATION_BODY_MOUNTED_TOOL_SET; + // Field assumed set by default. rosMsg.body_mounted_tool.body_tform_tool.position.x = 0.1; rosMsg.body_mounted_tool.body_tform_tool.position.y = 0.2; rosMsg.body_mounted_tool.body_tform_tool.position.z = 0.3; @@ -179,12 +172,13 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfToo } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfTaskSpecificationToProto) { - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification rosMsg; + using InverseKinematicsRequestOneOfTaskSpecification = + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification; + InverseKinematicsRequestOneOfTaskSpecification rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.task_specification_choice = - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_POSE_TASK_SET; - rosMsg.tool_pose_task.task_tform_desired_tool_is_set = true; + rosMsg.which = InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_POSE_TASK_SET; + // Field assumed set by default. rosMsg.tool_pose_task.task_tform_desired_tool.position.x = 0.1; rosMsg.tool_pose_task.task_tform_desired_tool.position.y = 0.2; rosMsg.tool_pose_task.task_tform_desired_tool.position.z = 0.3; @@ -211,12 +205,13 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfTas } TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfTaskSpecificationToProtoGaze) { - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification rosMsg; + using InverseKinematicsRequestOneOfTaskSpecification = + bosdyn_spot_api_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification; + InverseKinematicsRequestOneOfTaskSpecification rosMsg; bosdyn::api::spot::InverseKinematicsRequest protoMsg; - rosMsg.task_specification_choice = - bosdyn_msgs::msg::InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_GAZE_TASK_SET; - rosMsg.tool_gaze_task.task_tform_desired_tool_is_set = true; + rosMsg.which = InverseKinematicsRequestOneOfTaskSpecification::TASK_SPECIFICATION_TOOL_GAZE_TASK_SET; + // Field assumed set by default. rosMsg.tool_gaze_task.task_tform_desired_tool.position.x = 0.1; rosMsg.tool_gaze_task.task_tform_desired_tool.position.y = 0.2; rosMsg.tool_gaze_task.task_tform_desired_tool.position.z = 0.3; @@ -242,4 +237,42 @@ TEST(TestKinematicConversions, convertBosdynMsgsInverseKinematicsRequestOneOfTas protoMsg.tool_gaze_task().task_tform_desired_tool().rotation().z()); } +TEST(TestKinematicConversions, convertProtoToBosdynMsgsKinematicState) { + bosdyn::api::KinematicState protoMsg; + bosdyn_api_msgs::msg::KinematicState rosMsg; + + auto* joint_state = protoMsg.add_joint_states(); + joint_state->set_name("shoulder"); + joint_state->mutable_position()->set_value(0.0); + joint_state->mutable_velocity()->set_value(0.1); + joint_state->mutable_acceleration()->set_value(0.2); + joint_state->mutable_load()->set_value(0.5); + protoMsg.mutable_acquisition_timestamp()->set_seconds(1); + auto* snapshot = protoMsg.mutable_transforms_snapshot(); + auto& edge = (*snapshot->mutable_child_to_parent_edge_map())["arm"]; + edge.set_parent_frame_name("torso"); + edge.mutable_parent_tform_child()->mutable_position()->set_x(1.0); + protoMsg.mutable_velocity_of_body_in_vision()->mutable_linear()->set_x(1.0); + protoMsg.mutable_velocity_of_body_in_odom()->mutable_linear()->set_y(1.0); + + convertToRos(protoMsg, rosMsg); + + ASSERT_EQ(protoMsg.joint_states_size(), static_cast(rosMsg.joint_states.size())); + ASSERT_EQ(protoMsg.joint_states(0).name(), rosMsg.joint_states[0].name); + ASSERT_EQ(protoMsg.joint_states(0).position().value(), rosMsg.joint_states[0].position.data); + ASSERT_EQ(protoMsg.joint_states(0).velocity().value(), rosMsg.joint_states[0].velocity.data); + ASSERT_EQ(protoMsg.joint_states(0).acceleration().value(), rosMsg.joint_states[0].acceleration.data); + ASSERT_EQ(protoMsg.joint_states(0).load().value(), rosMsg.joint_states[0].load.data); + ASSERT_EQ(protoMsg.transforms_snapshot().child_to_parent_edge_map().size(), + rosMsg.transforms_snapshot.child_to_parent_edge_map.size()); + ASSERT_EQ(rosMsg.transforms_snapshot.child_to_parent_edge_map[0].key, "arm"); + ASSERT_EQ(protoMsg.transforms_snapshot().child_to_parent_edge_map().at("arm").parent_frame_name(), + rosMsg.transforms_snapshot.child_to_parent_edge_map[0].value.parent_frame_name); + ASSERT_EQ(protoMsg.transforms_snapshot().child_to_parent_edge_map().at("arm").parent_tform_child().position().x(), + rosMsg.transforms_snapshot.child_to_parent_edge_map[0].value.parent_tform_child.position.x); + ASSERT_EQ(protoMsg.acquisition_timestamp().seconds(), rosMsg.acquisition_timestamp.sec); + ASSERT_EQ(protoMsg.velocity_of_body_in_vision().linear().x(), rosMsg.velocity_of_body_in_vision.linear.x); + ASSERT_EQ(protoMsg.velocity_of_body_in_odom().linear().y(), rosMsg.velocity_of_body_in_odom.linear.y); +} + } // namespace spot_ros2::test diff --git a/spot_driver/test/src/conversions/test_robot_state.cpp b/spot_driver/test/src/conversions/test_robot_state.cpp index 9beffa83c..9dc4bf657 100644 --- a/spot_driver/test/src/conversions/test_robot_state.cpp +++ b/spot_driver/test/src/conversions/test_robot_state.cpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include #include @@ -36,6 +36,7 @@ using ::testing::Field; using ::testing::IsEmpty; using ::testing::IsFalse; using ::testing::IsTrue; +using ::testing::Not; using ::testing::SizeIs; using ::testing::StrEq; using ::testing::UnorderedElementsAre; @@ -699,20 +700,24 @@ TEST(RobotStateConversions, TestGetManipulatorState) { // THEN all the output fields are set, and contain the same values as the inputs EXPECT_THAT(out->gripper_open_percentage, DoubleEq(50.0)); EXPECT_THAT(out->is_gripper_holding_item, IsTrue()); - EXPECT_THAT(out->carry_state.value, Eq(bosdyn_msgs::msg::ManipulatorStateCarryState::CARRY_STATE_NOT_CARRIABLE)); - EXPECT_THAT(out->stow_state.value, Eq(bosdyn_msgs::msg::ManipulatorStateStowState::STOWSTATE_DEPLOYED)); - EXPECT_THAT(out->estimated_end_effector_force_in_hand_is_set, IsTrue()); + using ManipulatorStateCarryState = bosdyn_api_msgs::msg::ManipulatorStateCarryState; + using ManipulatorStateStowState = bosdyn_api_msgs::msg::ManipulatorStateStowState; + EXPECT_THAT(out->carry_state.value, Eq(ManipulatorStateCarryState::CARRY_STATE_NOT_CARRIABLE)); + EXPECT_THAT(out->stow_state.value, Eq(ManipulatorStateStowState::STOWSTATE_DEPLOYED)); + + using ManipulatorState = bosdyn_api_msgs::msg::ManipulatorState; + EXPECT_THAT(out->has_field, HasEnabledBit(ManipulatorState::ESTIMATED_END_EFFECTOR_FORCE_IN_HAND_FIELD_SET)); EXPECT_THAT(out->estimated_end_effector_force_in_hand, GeometryMsgsVector3Eq(force_in_hand.x(), force_in_hand.y(), force_in_hand.z())); - EXPECT_THAT(out->velocity_of_hand_in_vision_is_set, IsTrue()); + EXPECT_THAT(out->has_field, HasEnabledBit(ManipulatorState::VELOCITY_OF_HAND_IN_VISION_FIELD_SET)); EXPECT_THAT(out->velocity_of_hand_in_vision, GeometryMsgsTwistEq(velocity_hand_vision.linear().x(), velocity_hand_vision.linear().y(), velocity_hand_vision.linear().z(), velocity_hand_vision.angular().x(), velocity_hand_vision.angular().y(), velocity_hand_vision.angular().z())); - EXPECT_THAT(out->velocity_of_hand_in_odom_is_set, IsTrue()); + EXPECT_THAT(out->has_field, HasEnabledBit(ManipulatorState::VELOCITY_OF_HAND_IN_ODOM_FIELD_SET)); EXPECT_THAT(out->velocity_of_hand_in_odom, GeometryMsgsTwistEq(velocity_hand_odom.linear().x(), velocity_hand_odom.linear().y(), velocity_hand_odom.linear().z(), velocity_hand_odom.angular().x(), @@ -740,7 +745,8 @@ TEST(RobotStateConversions, TestGetManipulatorStateNoForceInHand) { // THEN the conversion does not succeed EXPECT_THAT(out.has_value(), IsTrue()); - EXPECT_THAT(out->estimated_end_effector_force_in_hand_is_set, IsFalse()); + using ManipulatorState = bosdyn_api_msgs::msg::ManipulatorState; + EXPECT_THAT(out->has_field, Not(HasEnabledBit(ManipulatorState::ESTIMATED_END_EFFECTOR_FORCE_IN_HAND_FIELD_SET))); } TEST(RobotStateConversions, TestGetEndEffectorForce) { diff --git a/spot_driver/test/src/kinematic/test_kinematic_service.cpp b/spot_driver/test/src/kinematic/test_kinematic_service.cpp index d62603050..9287691a3 100644 --- a/spot_driver/test/src/kinematic/test_kinematic_service.cpp +++ b/spot_driver/test/src/kinematic/test_kinematic_service.cpp @@ -70,7 +70,7 @@ TEST(TestKinematicService, getSolutions) { // THEN the IK response indicates that the request succeeds. - ASSERT_EQ(response->response.status.value, bosdyn_msgs::msg::InverseKinematicsResponseStatus::STATUS_OK); + ASSERT_EQ(response->response.status.value, bosdyn_spot_api_msgs::msg::InverseKinematicsResponseStatus::STATUS_OK); } /** @@ -91,7 +91,8 @@ TEST(TestKinematicService, getSolutionsException) { auto response = std::make_shared(); ik_service->getSolutions(request, response); - ASSERT_EQ(response->response.status.value, bosdyn_msgs::msg::InverseKinematicsResponseStatus::STATUS_UNKNOWN); + ASSERT_EQ(response->response.status.value, + bosdyn_spot_api_msgs::msg::InverseKinematicsResponseStatus::STATUS_UNKNOWN); } } // namespace spot_ros2::kinematic::test diff --git a/spot_driver/test/src/test_clock_skew.cpp b/spot_driver/test/src/test_clock_skew.cpp index 4d438f294..6dfb50e5a 100644 --- a/spot_driver/test/src/test_clock_skew.cpp +++ b/spot_driver/test/src/test_clock_skew.cpp @@ -24,238 +24,241 @@ TEST(TestClockSkewRobotToLocal, ZeroSkew) { // THEN the output timestamp is identical to the input timestamp EXPECT_THAT(out.sec, testing::Eq(1000)); - EXPECT_THAT(out.nanosec, testing::Eq(500)); + EXPECT_THAT(out.nanosec, testing::Eq(500u)); } -TEST(TestClockSkewRobotToLocal, PositiveSkew) { - // GIVEN a positive timestamp and a clock skew with positive seconds and nanoseconds fields - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(1000); - timestamp.set_nanos(500); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(100); - clock_skew.set_nanos(10); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN the output timestamp is decreased by the values in the clock skew - EXPECT_THAT(out.sec, testing::Eq(900)); - EXPECT_THAT(out.nanosec, testing::Eq(490)); -} - -TEST(TestClockSkewRobotToLocal, NegativeSkew) { - // GIVEN a positive timestamp and a clock skew with negative seconds and nanoseconds fields - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(1000); - timestamp.set_nanos(500); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(-100); - clock_skew.set_nanos(-10); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN the output timestamp is increased by the values in the clock skew - EXPECT_THAT(out.sec, testing::Eq(1100)); - EXPECT_THAT(out.nanosec, testing::Eq(510)); -} - -TEST(TestClockSkewRobotToLocal, PositiveSkewNanosecsCarry) { - // GIVEN a positive timestamp and a clock skew where the number of seconds is zero and the number of nanoseconds in - // the clock skew is greater than the number of nanoseconds in the timestamp - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(1000); - timestamp.set_nanos(100'000'000); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(0); - clock_skew.set_nanos(200'000'000); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN a second is carried over into the nanoseconds field - EXPECT_THAT(out.sec, testing::Eq(999)); - EXPECT_THAT(out.nanosec, testing::Eq(900'000'000)); -} - -TEST(TestClockSkewRobotToLocal, NegativeSkewNanosecsCarry) { - // GIVEN a positive timestamp and a clock skew where the number of seconds is zero and the number of nanoseconds in - // the clock skew is negative and of sufficient magnitude to add to greater than one full second when summed with the - // timetamp nanoseconds - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(1000); - timestamp.set_nanos(900'000'000); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(0); - clock_skew.set_nanos(-200'000'000); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN a full second and the remainder of nanoseconds are added to the timestamp - EXPECT_THAT(out.sec, testing::Eq(1001)); - EXPECT_THAT(out.nanosec, testing::Eq(100'000'000)); -} - -TEST(TestClockSkewRobotToLocal, HandleNegativeInputTimestamp) { - // GIVEN a timestamp with a negative number of seconds and an all-zero clock skew - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(-1); - timestamp.set_nanos(0); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(0); - clock_skew.set_nanos(0); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN an all-zero timestamp is output - EXPECT_THAT(out.sec, testing::Eq(0)); - EXPECT_THAT(out.nanosec, testing::Eq(0)); -} - -TEST(TestClockSkewRobotToLocal, HandleNegativeUnskewedTimestamp) { - // GIVEN a timestamp with a positive number of seconds and a positive clock skew with a greater number of seconds than - // the timestamp - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(1000); - timestamp.set_nanos(0); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(1001); - clock_skew.set_nanos(0); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN an all-zero timestamp is output - EXPECT_THAT(out.sec, testing::Eq(0)); - EXPECT_THAT(out.nanosec, testing::Eq(0)); -} - -TEST(TestClockSkewRobotToLocal, HandleNegativeUnskewedTimestampFromNanoseconds) { - // GIVEN an all-zero timestamp and a positive clock skew with a non-zero number of nanoseconds - google::protobuf::Timestamp timestamp; - timestamp.set_seconds(0); - timestamp.set_nanos(0); - google::protobuf::Duration clock_skew; - clock_skew.set_seconds(0); - clock_skew.set_nanos(1); - - // WHEN we apply the clock skew to the timestamp - const auto out = robotTimeToLocalTime(timestamp, clock_skew); - - // THEN an all-zero timestamp is output - EXPECT_THAT(out.sec, testing::Eq(0)); - EXPECT_THAT(out.nanosec, testing::Eq(0)); -} - -TEST(TestClockSkewLocalToRobot, ZeroSkew) { - // GIVEN a positive timestamp and an all-zero clock skew - const auto timestamp = builtin_interfaces::build