From 60280eda3caafa7a133c814f62d516e92da36b55 Mon Sep 17 00:00:00 2001 From: Kazuto Murase Date: Thu, 16 May 2024 17:09:27 +0900 Subject: [PATCH] bump version to v3.0.14 (#87) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit カチャカソフトウェア [v3.0.14](https://kachaka.zendesk.com/hc/ja/articles/9738402154639-%E3%82%AB%E3%83%81%E3%83%A3%E3%82%AB%E3%82%BD%E3%83%95%E3%83%88%E3%82%A6%E3%82%A7%E3%82%A2%E3%82%A2%E3%83%83%E3%83%97%E3%83%87%E3%83%BC%E3%83%88%E3%81%AE%E3%81%8A%E7%9F%A5%E3%82%89%E3%81%9B-Ver-3-0-14) に合わせてカチャカAPIを更新します。 変更点は、以下です。 新機能として、以下をサポートします。 - GetBatteryInfo: バッテリー情報の取得 - GetTofCameraXXX: ToFセンサ画像/情報の取得 - SwitchMap: マップの切り替え - SetFront/BackTorchIntensity: フロント・バックLEDライトの点灯 - ActivateLaserScan: LiDAR強制起動 - MoveForwardCommand: 前進コマンド - RotateInPlaceCommand: その場回転コマンド --- README.md | 11 +- protos/kachaka-api.proto | 83 +++++++ python/demos/get_laser_scan.ipynb | 64 +++-- python/kachaka_api/aio/base.py | 27 ++ python/kachaka_api/base.py | 27 ++ .../kachaka_api/generated/kachaka_api_pb2.py | 232 ++++++++++-------- .../kachaka_api/generated/kachaka_api_pb2.pyi | 93 ++++++- .../generated/kachaka_api_pb2_grpc.py | 231 +++++++++++++++++ python/kachaka_api/util/vision.py | 44 +++- ros2/kachaka_description/config/kachaka.rviz | 81 ++++-- ros2/kachaka_grpc_ros2_bridge/CMakeLists.txt | 16 ++ .../launch/grpc_ros2_bridge.launch.xml | 18 ++ .../src/camera_bridge.hpp | 7 +- .../src/component/back_camera_component.cpp | 2 +- .../src/component/front_camera_component.cpp | 2 +- .../src/component/tof_camera_component.cpp | 60 +++++ .../src/component/torch_component.cpp | 101 ++++++++ 17 files changed, 949 insertions(+), 150 deletions(-) create mode 100644 ros2/kachaka_grpc_ros2_bridge/src/component/tof_camera_component.cpp create mode 100644 ros2/kachaka_grpc_ros2_bridge/src/component/torch_component.cpp diff --git a/README.md b/README.md index c638886..d2fe3f3 100644 --- a/README.md +++ b/README.md @@ -97,13 +97,14 @@ ![kachaka-api](docs/images/kachka-api.png) -## 前提条件 -* カチャカ本体内で動作するJupyterLabに関しては、ブラウザのみ用意すれば使用する事ができます。 +## 対応環境・言語 + +* カチャカ本体内で動作するJupyterLabを利用することで、OSを問わずWebブラウザのみ用意すれば開発を行うことができます。 * 対応ブラウザについては、[JupyterLab公式ドキュメント](https://jupyterlab.readthedocs.io/en/stable/getting_started/installation.html#supported-browsers)をご確認ください。 -* カチャカの外部から本書の手順に従ってカチャカAPIを使用する場合には、以下の条件に準拠したソフトウェアをインストールしたPCが必要となります。 - * OS - * Ubuntu 22.04 LTS +* カチャカ外部のPCからAPIを利用することも可能で、本ドキュメントの内容は以下の環境にて確認していますが、多くはmacOSやWindowsなど他の環境でも可能です。 + * 動作確認済みのOS + * Ubuntu 22.04 LTS * 開発言語 * Python3.10 * ROS 2(使用する場合) diff --git a/protos/kachaka-api.proto b/protos/kachaka-api.proto index ce666c9..8c7929d 100644 --- a/protos/kachaka-api.proto +++ b/protos/kachaka-api.proto @@ -72,6 +72,14 @@ message TwistWithCovariance { repeated double covariance = 2; } +enum PowerSupplyStatus { + POWER_SUPPLY_STATUS_UNSPECIFIED = 0; + POWER_SUPPLY_STATUS_CHARGING = 1; + POWER_SUPPLY_STATUS_DISCHARGING = 2; + POWER_SUPPLY_STATUS_NOT_CHARGING = 3; + POWER_SUPPLY_STATUS_FULL = 4; +} + message Map { bytes data = 1; // uint8[] string name = 2; @@ -242,6 +250,8 @@ message Command { SpeakCommand speak_command = 12; MoveToPoseCommand move_to_pose_command = 13; LockCommand lock_command = 15; + MoveForwardCommand move_forward_command = 16; + RotateInPlaceCommand rotate_in_place_command = 17; } } @@ -285,6 +295,14 @@ message LockCommand { double duration_sec = 1; } +message MoveForwardCommand { + double distance_meter = 1; +} + +message RotateInPlaceCommand { + double angle_radian = 1; +} + enum CommandState { COMMAND_STATE_UNSPECIFIED = 0; COMMAND_STATE_PENDING = 1; // No command is running. Waiting for requests. @@ -314,6 +332,12 @@ message GetRobotPoseResponse { Pose pose = 2; } +message GetBatteryInfoResponse { + Metadata metadata = 1; + double remaining_percentage = 2; // [0, 100] + PowerSupplyStatus power_supply_status = 3; +} + message GetPngMapResponse { Metadata metadata = 1; Map map = 2; @@ -376,11 +400,29 @@ message GetBackCameraRosCompressedImageResponse { RosCompressedImage image = 2; } +message GetTofCameraRosCameraInfoResponse { + Metadata metadata = 1; + RosCameraInfo camera_info = 2; +} + +message GetTofCameraRosImageResponse { + Metadata metadata = 1; + RosImage image = 2; + bool is_available = 3; +} + +message GetTofCameraRosCompressedImageResponse { + Metadata metadata = 1; + RosCompressedImage image = 2; + bool is_available = 3; +} + message StartCommandRequest { Command command = 1; bool cancel_all = 2; string tts_on_success = 3; string title = 4; + bool deferrable = 5; } message StartCommandResponse { @@ -462,6 +504,22 @@ message GetManualControlEnabledResponse { bool enabled = 2; } +message SetFrontTorchIntensityRequest { + int32 intensity = 1; // [0, 255] +} + +message SetFrontTorchIntensityResponse { + Result result = 1; +} + +message SetBackTorchIntensityRequest { + int32 intensity = 1; // [0, 255] +} + +message SetBackTorchIntensityResponse { + Result result = 1; +} + message SetRobotVelocityRequest { double linear = 1; // [-1, 1] double angular = 2; // [-1, 1] @@ -471,6 +529,14 @@ message SetRobotVelocityResponse { Result result = 1; } +message ActivateLaserScanRequest { + double duration_sec = 1; +} + +message ActivateLaserScanResponse { + Result result = 1; +} + message GetStaticTransformResponse { Metadata metadata = 1; repeated RosTransformStamped transforms = 2; @@ -545,11 +611,21 @@ message GetHistoryListResponse { repeated History histories = 2; } +message SwitchMapRequest { + string map_id = 1; + Pose initial_pose = 2; // use the charger pose if the message is empty +} + +message SwitchMapResponse { + Result result = 1; +} + // Services service KachakaApi { rpc GetRobotSerialNumber (GetRequest) returns (GetRobotSerialNumberResponse); rpc GetRobotVersion (GetRequest) returns (GetRobotVersionResponse); rpc GetRobotPose (GetRequest) returns (GetRobotPoseResponse); + rpc GetBatteryInfo (GetRequest) returns (GetBatteryInfoResponse); rpc GetPngMap (GetRequest) returns (GetPngMapResponse); rpc GetObjectDetection (GetRequest) returns (GetObjectDetectionResponse); rpc GetObjectDetectionFeatures (GetRequest) returns (GetObjectDetectionFeaturesResponse); @@ -562,6 +638,9 @@ service KachakaApi { rpc GetBackCameraRosCameraInfo (GetRequest) returns (GetBackCameraRosCameraInfoResponse); rpc GetBackCameraRosImage (GetRequest) returns (GetBackCameraRosImageResponse); rpc GetBackCameraRosCompressedImage (GetRequest) returns (GetBackCameraRosCompressedImageResponse); + rpc GetTofCameraRosCameraInfo (GetRequest) returns (GetTofCameraRosCameraInfoResponse); + rpc GetTofCameraRosImage (GetRequest) returns (GetTofCameraRosImageResponse); + rpc GetTofCameraRosCompressedImage (GetRequest) returns (GetTofCameraRosCompressedImageResponse); rpc StartCommand (StartCommandRequest) returns (StartCommandResponse); rpc CancelCommand (EmptyRequest) returns (CancelCommandResponse); rpc GetCommandState (GetRequest) returns (GetCommandStateResponse); @@ -575,7 +654,10 @@ service KachakaApi { rpc GetAutoHomingEnabled (GetRequest) returns (GetAutoHomingEnabledResponse); rpc SetManualControlEnabled (SetManualControlEnabledRequest) returns (SetManualControlEnabledResponse); rpc GetManualControlEnabled (GetRequest) returns (GetManualControlEnabledResponse); + rpc SetFrontTorchIntensity (SetFrontTorchIntensityRequest) returns (SetFrontTorchIntensityResponse); + rpc SetBackTorchIntensity (SetBackTorchIntensityRequest) returns (SetBackTorchIntensityResponse); rpc SetRobotVelocity (SetRobotVelocityRequest) returns (SetRobotVelocityResponse); + rpc ActivateLaserScan (ActivateLaserScanRequest) returns (ActivateLaserScanResponse); rpc GetMapList (GetRequest) returns (GetMapListResponse); rpc GetCurrentMapId (GetRequest) returns (GetCurrentMapIdResponse); rpc LoadMapPreview (LoadMapPreviewRequest) returns (LoadMapPreviewResponse); @@ -584,4 +666,5 @@ service KachakaApi { rpc GetHistoryList (GetRequest) returns (GetHistoryListResponse); rpc GetStaticTransform (GetRequest) returns (GetStaticTransformResponse); rpc GetDynamicTransform (EmptyRequest) returns (stream GetDynamicTransformResponse); + rpc SwitchMap (SwitchMapRequest) returns (SwitchMapResponse); } diff --git a/python/demos/get_laser_scan.ipynb b/python/demos/get_laser_scan.ipynb index 3646ae5..154ca75 100644 --- a/python/demos/get_laser_scan.ipynb +++ b/python/demos/get_laser_scan.ipynb @@ -27,25 +27,55 @@ "client = kachaka_api.aio.KachakaApiClient()\n", "await client.set_manual_control_enabled(True)\n", "\n", - "async for scan in client.ros_laser_scan.stream():\n", - " clear_output(wait=True)\n", - " fig = plt.figure(figsize=(5, 5))\n", "\n", - " n = len(scan.ranges)\n", - " x = list(range(n))\n", - " y = list(range(n))\n", - " for i in range(n):\n", - " theta = scan.angle_min + scan.angle_increment * i\n", - " x[i] = scan.ranges[i] * math.cos(theta)\n", - " y[i] = scan.ranges[i] * math.sin(theta)\n", + "async def get_and_show_laser_scan_loop():\n", + " async for scan in client.ros_laser_scan.stream():\n", + " clear_output(wait=True)\n", + " fig = plt.figure(figsize=(5, 5))\n", "\n", - " plt.plot(0, 0, \"o\", color=\"black\")\n", - " plt.plot(x, y, \".\")\n", - " plt.xlim(-6.0, 6.0)\n", - " plt.ylim(-6.0, 6.0)\n", - " plt.grid(True)\n", - " plt.gca().set_aspect(\"equal\", adjustable=\"box\")\n", - " plt.show()" + " n = len(scan.ranges)\n", + " x = list(range(n))\n", + " y = list(range(n))\n", + " for i in range(n):\n", + " theta = scan.angle_min + scan.angle_increment * i\n", + " x[i] = scan.ranges[i] * math.cos(theta)\n", + " y[i] = scan.ranges[i] * math.sin(theta)\n", + "\n", + " plt.plot(0, 0, \"o\", color=\"black\")\n", + " plt.plot(x, y, \".\")\n", + " plt.xlim(-6.0, 6.0)\n", + " plt.ylim(-6.0, 6.0)\n", + " plt.grid(True)\n", + " plt.gca().set_aspect(\"equal\", adjustable=\"box\")\n", + " plt.show()\n", + "\n", + "\n", + "await get_and_show_laser_scan_loop()" + ] + }, + { + "cell_type": "markdown", + "id": "d43ec70a-3f57-4b72-9ba8-097f9d87b361", + "metadata": {}, + "source": [ + "上記の方法は、手動操縦モードをONにすることでLiDARを動かしており、カチャカが動かずしばらく経つとスキャンが止まります。\n", + "以下のようにActivatorを使うことで、カチャカが静止している状態でもスキャンを継続することができます。\n", + "\n", + "ただし**必要以上にスキャンを動かし続けると、LiDARの製品寿命を大幅に縮めることになります**ので、ご注意下さい。" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4c65434b-bc3b-4d19-9c7f-247e7668dcf1", + "metadata": {}, + "outputs": [], + "source": [ + "from kachaka_api.util.vision import LaserScanActivator\n", + "\n", + "activator = LaserScanActivator()\n", + "with activator.activate():\n", + " await get_and_show_laser_scan_loop()" ] } ], diff --git a/python/kachaka_api/aio/base.py b/python/kachaka_api/aio/base.py index 768a83b..d485076 100644 --- a/python/kachaka_api/aio/base.py +++ b/python/kachaka_api/aio/base.py @@ -137,6 +137,33 @@ async def get_back_camera_ros_compressed_image( ) return response.image + async def get_tof_camera_ros_camera_info(self) -> pb2.RosCameraInfo: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosCameraInfoResponse = ( + await self.stub.GetTofCameraRosCameraInfo(request) + ) + return response.camera_info + + async def get_tof_camera_ros_image(self) -> pb2.RosImage: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosImageResponse = ( + await self.stub.GetTofCameraRosImage(request) + ) + if not response.is_available: + raise Exception("tof is not available on charger.") + return response.image + + async def get_tof_camera_ros_compressed_image( + self, + ) -> pb2.RosCompressedImage: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosCompressedImageResponse = ( + await self.stub.GetTofCameraRosCompressedImage(request) + ) + if not response.is_available: + raise Exception("tof is not available on charger.") + return response.image + async def start_command( self, command: pb2.Command, diff --git a/python/kachaka_api/base.py b/python/kachaka_api/base.py index 60614b5..7eb0deb 100644 --- a/python/kachaka_api/base.py +++ b/python/kachaka_api/base.py @@ -136,6 +136,33 @@ def get_back_camera_ros_compressed_image( ) return response.image + def get_tof_camera_ros_camera_info(self) -> pb2.RosCameraInfo: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosCameraInfoResponse = ( + self.stub.GetTofCameraRosCameraInfo(request) + ) + return response.camera_info + + def get_tof_camera_ros_image(self) -> pb2.RosImage: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosImageResponse = ( + self.stub.GetTofCameraRosImage(request) + ) + if not response.is_available: + raise Exception("tof is not available on charger.") + return response.image + + def get_tof_camera_ros_compressed_image( + self, + ) -> pb2.RosCompressedImage: + request = pb2.GetRequest() + response: pb2.GetTofCameraRosCompressedImageResponse = ( + self.stub.GetTofCameraRosCompressedImage(request) + ) + if not response.is_available: + raise Exception("tof is not available on charger.") + return response.image + def start_command( self, command: pb2.Command, diff --git a/python/kachaka_api/generated/kachaka_api_pb2.py b/python/kachaka_api/generated/kachaka_api_pb2.py index 34c5adc..40724a4 100644 --- a/python/kachaka_api/generated/kachaka_api_pb2.py +++ b/python/kachaka_api/generated/kachaka_api_pb2.py @@ -14,23 +14,25 @@ -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11kachaka-api.proto\x12\x0bkachaka_api\"\x1a\n\x08Metadata\x12\x0e\n\x06\x63ursor\x18\x01 \x01(\x10\"-\n\x06Result\x12\x0f\n\x07success\x18\x01 \x01(\x08\x12\x12\n\nerror_code\x18\x03 \x01(\x05\"\x1b\n\x05\x45rror\x12\x12\n\nerror_code\x18\x02 \x01(\x05\"1\n\tRosHeader\x12\x12\n\nstamp_nsec\x18\x01 \x01(\x03\x12\x10\n\x08\x66rame_id\x18\x02 \x01(\t\"+\n\x04Pose\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\r\n\x05theta\x18\x03 \x01(\x01\"*\n\x07Vector3\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"8\n\nQuaternion\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"^\n\x06Pose3d\x12&\n\x08position\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12,\n\x0borientation\x18\x02 \x01(\x0b\x32\x17.kachaka_api.Quaternion\"T\n\x05Twist\x12$\n\x06linear\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12%\n\x07\x61ngular\x18\x02 \x01(\x0b\x32\x14.kachaka_api.Vector3\"M\n\x14Pose3dWithCovariance\x12!\n\x04pose\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Pose3d\x12\x12\n\ncovariance\x18\x02 \x03(\x01\"L\n\x13TwistWithCovariance\x12!\n\x05twist\x18\x01 \x01(\x0b\x32\x12.kachaka_api.Twist\x12\x12\n\ncovariance\x18\x02 \x03(\x01\"w\n\x03Map\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x12\n\nresolution\x18\x03 \x01(\x01\x12\r\n\x05width\x18\x04 \x01(\x05\x12\x0e\n\x06height\x18\x05 \x01(\x05\x12!\n\x06origin\x18\x06 \x01(\x0b\x32\x11.kachaka_api.Pose\"\xe0\x01\n\x08Location\x12\n\n\x02id\x18\x01 \x01(\t\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x1f\n\x04pose\x18\x03 \x01(\x0b\x32\x11.kachaka_api.Pose\x12\'\n\x04type\x18\x04 \x01(\x0e\x32\x19.kachaka_api.LocationType\x12%\n\x1dundock_shelf_aligning_to_wall\x18\x05 \x01(\x08\x12\'\n\x1fundock_shelf_avoiding_obstacles\x18\x06 \x01(\x08\x12 \n\x18ignore_voice_recognition\x18\x07 \x01(\x08\"9\n\tShelfSize\x12\r\n\x05width\x18\x01 \x01(\x01\x12\r\n\x05\x64\x65pth\x18\x02 \x01(\x01\x12\x0e\n\x06height\x18\x03 \x01(\x01\"3\n\x10RecognizableName\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x11\n\tdeletable\x18\x02 \x01(\x08\"\xc2\x02\n\x05Shelf\x12\n\n\x02id\x18\x01 \x01(\t\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x1f\n\x04pose\x18\x03 \x01(\x0b\x32\x11.kachaka_api.Pose\x12$\n\x04size\x18\x04 \x01(\x0b\x32\x16.kachaka_api.ShelfSize\x12\x30\n\nappearance\x18\x05 \x01(\x0e\x32\x1c.kachaka_api.ShelfAppearance\x12\x39\n\x12recognizable_names\x18\x07 \x03(\x0b\x32\x1d.kachaka_api.RecognizableName\x12\x18\n\x10home_location_id\x18\x08 \x01(\t\x12/\n\nspeed_mode\x18\t \x01(\x0e\x32\x1b.kachaka_api.ShelfSpeedMode\x12 \n\x18ignore_voice_recognition\x18\n \x01(\x08\"\xae\x02\n\x06RosImu\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12,\n\x0borientation\x18\x02 \x01(\x0b\x32\x17.kachaka_api.Quaternion\x12\x1e\n\x16orientation_covariance\x18\x03 \x03(\x01\x12.\n\x10\x61ngular_velocity\x18\x04 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12#\n\x1b\x61ngular_velocity_covariance\x18\x05 \x03(\x01\x12\x31\n\x13linear_acceleration\x18\x06 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12&\n\x1elinear_acceleration_covariance\x18\x07 \x03(\x01\"\xaf\x01\n\x0bRosOdometry\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x16\n\x0e\x63hild_frame_id\x18\x02 \x01(\t\x12/\n\x04pose\x18\x03 \x01(\x0b\x32!.kachaka_api.Pose3dWithCovariance\x12/\n\x05twist\x18\x04 \x01(\x0b\x32 .kachaka_api.TwistWithCovariance\"\xeb\x01\n\x0cRosLaserScan\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x11\n\tangle_min\x18\x02 \x01(\x01\x12\x11\n\tangle_max\x18\x03 \x01(\x01\x12\x17\n\x0f\x61ngle_increment\x18\x04 \x01(\x01\x12\x16\n\x0etime_increment\x18\x05 \x01(\x01\x12\x11\n\tscan_time\x18\x06 \x01(\x01\x12\x11\n\trange_min\x18\x07 \x01(\x01\x12\x11\n\trange_max\x18\x08 \x01(\x01\x12\x0e\n\x06ranges\x18\t \x03(\x01\x12\x13\n\x0bintensities\x18\n \x03(\x01\"i\n\x10RegionOfInterest\x12\x10\n\x08x_offset\x18\x01 \x01(\r\x12\x10\n\x08y_offset\x18\x02 \x01(\r\x12\x0e\n\x06height\x18\x03 \x01(\r\x12\r\n\x05width\x18\x04 \x01(\r\x12\x12\n\ndo_rectify\x18\x05 \x01(\x08\"\xee\x01\n\rRosCameraInfo\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06height\x18\x02 \x01(\r\x12\r\n\x05width\x18\x03 \x01(\r\x12\x18\n\x10\x64istortion_model\x18\x04 \x01(\t\x12\t\n\x01\x44\x18\x05 \x03(\x01\x12\t\n\x01K\x18\x06 \x03(\x01\x12\t\n\x01R\x18\x07 \x03(\x01\x12\t\n\x01P\x18\x08 \x03(\x01\x12\x11\n\tbinning_x\x18\t \x01(\r\x12\x11\n\tbinning_y\x18\n \x01(\r\x12*\n\x03roi\x18\x0b \x01(\x0b\x32\x1d.kachaka_api.RegionOfInterest\"\x95\x01\n\x08RosImage\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06height\x18\x02 \x01(\r\x12\r\n\x05width\x18\x03 \x01(\r\x12\x10\n\x08\x65ncoding\x18\x04 \x01(\t\x12\x14\n\x0cis_bigendian\x18\x05 \x01(\x08\x12\x0c\n\x04step\x18\x06 \x01(\r\x12\x0c\n\x04\x64\x61ta\x18\x07 \x01(\x0c\"\xab\x01\n\x13RosTransformStamped\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x16\n\x0e\x63hild_frame_id\x18\x02 \x01(\t\x12)\n\x0btranslation\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12)\n\x08rotation\x18\x04 \x01(\x0b\x32\x17.kachaka_api.Quaternion\"Z\n\x12RosCompressedImage\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06\x66ormat\x18\x02 \x01(\t\x12\x0c\n\x04\x64\x61ta\x18\x03 \x01(\x0c\"t\n\x0fObjectDetection\x12\r\n\x05label\x18\x01 \x01(\r\x12*\n\x03roi\x18\x02 \x01(\x0b\x32\x1d.kachaka_api.RegionOfInterest\x12\r\n\x05score\x18\x03 \x01(\x02\x12\x17\n\x0f\x64istance_median\x18\x04 \x01(\x01\"D\n\x17ObjectDetectionFeatures\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05shape\x18\x02 \x03(\r\x12\x0c\n\x04\x64\x61ta\x18\x03 \x03(\x02\"\xbd\x04\n\x07\x43ommand\x12;\n\x12move_shelf_command\x18\x01 \x01(\x0b\x32\x1d.kachaka_api.MoveShelfCommandH\x00\x12?\n\x14return_shelf_command\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.ReturnShelfCommandH\x00\x12?\n\x14undock_shelf_command\x18\x05 \x01(\x0b\x32\x1f.kachaka_api.UndockShelfCommandH\x00\x12\x46\n\x18move_to_location_command\x18\x07 \x01(\x0b\x32\".kachaka_api.MoveToLocationCommandH\x00\x12=\n\x13return_home_command\x18\x08 \x01(\x0b\x32\x1e.kachaka_api.ReturnHomeCommandH\x00\x12;\n\x12\x64ock_shelf_command\x18\t \x01(\x0b\x32\x1d.kachaka_api.DockShelfCommandH\x00\x12\x32\n\rspeak_command\x18\x0c \x01(\x0b\x32\x19.kachaka_api.SpeakCommandH\x00\x12>\n\x14move_to_pose_command\x18\r \x01(\x0b\x32\x1e.kachaka_api.MoveToPoseCommandH\x00\x12\x30\n\x0clock_command\x18\x0f \x01(\x0b\x32\x18.kachaka_api.LockCommandH\x00\x42\t\n\x07\x63ommand\"L\n\x10MoveShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\x12\x1f\n\x17\x64\x65stination_location_id\x18\x02 \x01(\t\"-\n\x12ReturnShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\"-\n\x12UndockShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\"3\n\x15MoveToLocationCommand\x12\x1a\n\x12target_location_id\x18\x01 \x01(\t\"\x13\n\x11ReturnHomeCommand\"\x12\n\x10\x44ockShelfCommand\"\x1c\n\x0cSpeakCommand\x12\x0c\n\x04text\x18\x01 \x01(\t\"6\n\x11MoveToPoseCommand\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\x0b\n\x03yaw\x18\x03 \x01(\x01\"#\n\x0bLockCommand\x12\x14\n\x0c\x64uration_sec\x18\x01 \x01(\x01\"\x0e\n\x0c\x45mptyRequest\"5\n\nGetRequest\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\"^\n\x1cGetRobotSerialNumberResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x15\n\rserial_number\x18\x02 \x01(\t\"S\n\x17GetRobotVersionResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07version\x18\x02 \x01(\t\"`\n\x14GetRobotPoseResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x1f\n\x04pose\x18\x02 \x01(\x0b\x32\x11.kachaka_api.Pose\"[\n\x11GetPngMapResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x1d\n\x03map\x18\x02 \x01(\x0b\x32\x10.kachaka_api.Map\"\x9c\x01\n\x1aGetObjectDetectionResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12&\n\x06header\x18\x02 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12-\n\x07objects\x18\x03 \x03(\x0b\x32\x1c.kachaka_api.ObjectDetection\"\xad\x01\n\"GetObjectDetectionFeaturesResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12&\n\x06header\x18\x02 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x36\n\x08\x66\x65\x61tures\x18\x03 \x03(\x0b\x32$.kachaka_api.ObjectDetectionFeatures\"^\n\x11GetRosImuResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12 \n\x03imu\x18\x02 \x01(\x0b\x32\x13.kachaka_api.RosImu\"m\n\x16GetRosOdometryResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12*\n\x08odometry\x18\x02 \x01(\x0b\x32\x18.kachaka_api.RosOdometry\"k\n\x17GetRosLaserScanResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\'\n\x04scan\x18\x02 \x01(\x0b\x32\x19.kachaka_api.RosLaserScan\"\x7f\n#GetFrontCameraRosCameraInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12/\n\x0b\x63\x61mera_info\x18\x02 \x01(\x0b\x32\x1a.kachaka_api.RosCameraInfo\"o\n\x1eGetFrontCameraRosImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12$\n\x05image\x18\x02 \x01(\x0b\x32\x15.kachaka_api.RosImage\"\x83\x01\n(GetFrontCameraRosCompressedImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12.\n\x05image\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.RosCompressedImage\"~\n\"GetBackCameraRosCameraInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12/\n\x0b\x63\x61mera_info\x18\x02 \x01(\x0b\x32\x1a.kachaka_api.RosCameraInfo\"n\n\x1dGetBackCameraRosImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12$\n\x05image\x18\x02 \x01(\x0b\x32\x15.kachaka_api.RosImage\"\x82\x01\n\'GetBackCameraRosCompressedImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12.\n\x05image\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.RosCompressedImage\"w\n\x13StartCommandRequest\x12%\n\x07\x63ommand\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncancel_all\x18\x02 \x01(\x08\x12\x16\n\x0etts_on_success\x18\x03 \x01(\t\x12\r\n\x05title\x18\x04 \x01(\t\"O\n\x14StartCommandResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x12\n\ncommand_id\x18\x02 \x01(\t\"c\n\x15\x43\x61ncelCommandResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12%\n\x07\x63ommand\x18\x02 \x01(\x0b\x32\x14.kachaka_api.Command\"\xa7\x01\n\x17GetCommandStateResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12(\n\x05state\x18\x02 \x01(\x0e\x32\x19.kachaka_api.CommandState\x12%\n\x07\x63ommand\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncommand_id\x18\x04 \x01(\t\"\xa7\x01\n\x1cGetLastCommandResultResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12#\n\x06result\x18\x02 \x01(\x0b\x32\x13.kachaka_api.Result\x12%\n\x07\x63ommand\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncommand_id\x18\x04 \x01(\t\"6\n\x0fProceedResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"\x86\x01\n\x14GetLocationsResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12(\n\tlocations\x18\x02 \x03(\x0b\x32\x15.kachaka_api.Location\x12\x1b\n\x13\x64\x65\x66\x61ult_location_id\x18\x03 \x01(\t\"b\n\x12GetShelvesResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12#\n\x07shelves\x18\x02 \x03(\x0b\x32\x12.kachaka_api.Shelf\"U\n\x18GetMovingShelfIdResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x10\n\x08shelf_id\x18\x02 \x01(\t\")\n\x15ResetShelfPoseRequest\x12\x10\n\x08shelf_id\x18\x01 \x01(\t\"=\n\x16ResetShelfPoseResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"-\n\x1bSetAutoHomingEnabledRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\"C\n\x1cSetAutoHomingEnabledResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"X\n\x1cGetAutoHomingEnabledResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07\x65nabled\x18\x02 \x01(\x08\"P\n\x1eSetManualControlEnabledRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\x12\x1e\n\x16use_shelf_registration\x18\x02 \x01(\x08\"F\n\x1fSetManualControlEnabledResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"[\n\x1fGetManualControlEnabledResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07\x65nabled\x18\x02 \x01(\x08\":\n\x17SetRobotVelocityRequest\x12\x0e\n\x06linear\x18\x01 \x01(\x01\x12\x0f\n\x07\x61ngular\x18\x02 \x01(\x01\"?\n\x18SetRobotVelocityResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"{\n\x1aGetStaticTransformResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x34\n\ntransforms\x18\x02 \x03(\x0b\x32 .kachaka_api.RosTransformStamped\"S\n\x1bGetDynamicTransformResponse\x12\x34\n\ntransforms\x18\x01 \x03(\x0b\x32 .kachaka_api.RosTransformStamped\"(\n\x0cMapListEntry\x12\n\n\x02id\x18\x02 \x01(\t\x12\x0c\n\x04name\x18\x01 \x01(\t\"r\n\x12GetMapListResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x33\n\x10map_list_entries\x18\x02 \x03(\x0b\x32\x19.kachaka_api.MapListEntry\"N\n\x17GetCurrentMapIdResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\n\n\x02id\x18\x02 \x01(\t\"\'\n\x15LoadMapPreviewRequest\x12\x0e\n\x06map_id\x18\x01 \x01(\t\"\\\n\x16LoadMapPreviewResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x1d\n\x03map\x18\x02 \x01(\x0b\x32\x10.kachaka_api.Map\"\"\n\x10\x45xportMapRequest\x12\x0e\n\x06map_id\x18\x01 \x01(\t\"\x83\x02\n\x11\x45xportMapResponse\x12I\n\x10middle_of_stream\x18\x01 \x01(\x0b\x32-.kachaka_api.ExportMapResponse.MiddleOfStreamH\x00\x12\x43\n\rend_of_stream\x18\x02 \x01(\x0b\x32*.kachaka_api.ExportMapResponse.EndOfStreamH\x00\x1a\x1e\n\x0eMiddleOfStream\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\x1a\x32\n\x0b\x45ndOfStream\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.ResultB\n\n\x08response\" \n\x10ImportMapRequest\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\"H\n\x11ImportMapResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x0e\n\x06map_id\x18\x02 \x01(\t\"\x80\x01\n\x07History\x12\n\n\x02id\x18\x01 \x01(\t\x12%\n\x07\x63ommand\x18\x04 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x0f\n\x07success\x18\x05 \x01(\x08\x12\x12\n\nerror_code\x18\x06 \x01(\x05\x12\x1d\n\x15\x63ommand_executed_time\x18\x07 \x01(\x03\"j\n\x16GetHistoryListResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\'\n\thistories\x18\x02 \x03(\x0b\x32\x14.kachaka_api.History*f\n\x0cLocationType\x12\x1d\n\x19LOCATION_TYPE_UNSPECIFIED\x10\x00\x12\x19\n\x15LOCATION_TYPE_CHARGER\x10\x01\x12\x1c\n\x18LOCATION_TYPE_SHELF_HOME\x10\x02*\xd4\x01\n\x0fShelfAppearance\x12 \n\x1cSHELF_APPEARANCE_UNSPECIFIED\x10\x00\x12\"\n\x1eSHELF_APPEARANCE_DEFAULT_SHELF\x10\x01\x12+\n\'SHELF_APPEARANCE_KACHAKA_SHELF_3DRAWERS\x10\x02\x12+\n\'SHELF_APPEARANCE_KACHAKA_SHELF_2DRAWERS\x10\x03\x12!\n\x1dSHELF_APPEARANCE_KACHAKA_BASE\x10\x08*i\n\x0eShelfSpeedMode\x12 \n\x1cSHELF_SPEED_MODE_UNSPECIFIED\x10\x00\x12\x18\n\x14SHELF_SPEED_MODE_LOW\x10\x01\x12\x1b\n\x17SHELF_SPEED_MODE_NORMAL\x10\x02*\x8d\x01\n\x0bObjectLabel\x12\x1c\n\x18OBJECT_LABEL_UNSPECIFIED\x10\x00\x12\x17\n\x13OBJECT_LABEL_PERSON\x10\x01\x12\x16\n\x12OBJECT_LABEL_SHELF\x10\x02\x12\x18\n\x14OBJECT_LABEL_CHARGER\x10\x03\x12\x15\n\x11OBJECT_LABEL_DOOR\x10\x04*c\n\x0c\x43ommandState\x12\x1d\n\x19\x43OMMAND_STATE_UNSPECIFIED\x10\x00\x12\x19\n\x15\x43OMMAND_STATE_PENDING\x10\x01\x12\x19\n\x15\x43OMMAND_STATE_RUNNING\x10\x02\x32\xdd\x19\n\nKachakaApi\x12Z\n\x14GetRobotSerialNumber\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetRobotSerialNumberResponse\x12P\n\x0fGetRobotVersion\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetRobotVersionResponse\x12J\n\x0cGetRobotPose\x12\x17.kachaka_api.GetRequest\x1a!.kachaka_api.GetRobotPoseResponse\x12\x44\n\tGetPngMap\x12\x17.kachaka_api.GetRequest\x1a\x1e.kachaka_api.GetPngMapResponse\x12V\n\x12GetObjectDetection\x12\x17.kachaka_api.GetRequest\x1a\'.kachaka_api.GetObjectDetectionResponse\x12\x66\n\x1aGetObjectDetectionFeatures\x12\x17.kachaka_api.GetRequest\x1a/.kachaka_api.GetObjectDetectionFeaturesResponse\x12\x44\n\tGetRosImu\x12\x17.kachaka_api.GetRequest\x1a\x1e.kachaka_api.GetRosImuResponse\x12N\n\x0eGetRosOdometry\x12\x17.kachaka_api.GetRequest\x1a#.kachaka_api.GetRosOdometryResponse\x12P\n\x0fGetRosLaserScan\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetRosLaserScanResponse\x12h\n\x1bGetFrontCameraRosCameraInfo\x12\x17.kachaka_api.GetRequest\x1a\x30.kachaka_api.GetFrontCameraRosCameraInfoResponse\x12^\n\x16GetFrontCameraRosImage\x12\x17.kachaka_api.GetRequest\x1a+.kachaka_api.GetFrontCameraRosImageResponse\x12r\n GetFrontCameraRosCompressedImage\x12\x17.kachaka_api.GetRequest\x1a\x35.kachaka_api.GetFrontCameraRosCompressedImageResponse\x12\x66\n\x1aGetBackCameraRosCameraInfo\x12\x17.kachaka_api.GetRequest\x1a/.kachaka_api.GetBackCameraRosCameraInfoResponse\x12\\\n\x15GetBackCameraRosImage\x12\x17.kachaka_api.GetRequest\x1a*.kachaka_api.GetBackCameraRosImageResponse\x12p\n\x1fGetBackCameraRosCompressedImage\x12\x17.kachaka_api.GetRequest\x1a\x34.kachaka_api.GetBackCameraRosCompressedImageResponse\x12S\n\x0cStartCommand\x12 .kachaka_api.StartCommandRequest\x1a!.kachaka_api.StartCommandResponse\x12N\n\rCancelCommand\x12\x19.kachaka_api.EmptyRequest\x1a\".kachaka_api.CancelCommandResponse\x12P\n\x0fGetCommandState\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetCommandStateResponse\x12Z\n\x14GetLastCommandResult\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetLastCommandResultResponse\x12\x42\n\x07Proceed\x12\x19.kachaka_api.EmptyRequest\x1a\x1c.kachaka_api.ProceedResponse\x12J\n\x0cGetLocations\x12\x17.kachaka_api.GetRequest\x1a!.kachaka_api.GetLocationsResponse\x12\x46\n\nGetShelves\x12\x17.kachaka_api.GetRequest\x1a\x1f.kachaka_api.GetShelvesResponse\x12R\n\x10GetMovingShelfId\x12\x17.kachaka_api.GetRequest\x1a%.kachaka_api.GetMovingShelfIdResponse\x12Y\n\x0eResetShelfPose\x12\".kachaka_api.ResetShelfPoseRequest\x1a#.kachaka_api.ResetShelfPoseResponse\x12k\n\x14SetAutoHomingEnabled\x12(.kachaka_api.SetAutoHomingEnabledRequest\x1a).kachaka_api.SetAutoHomingEnabledResponse\x12Z\n\x14GetAutoHomingEnabled\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetAutoHomingEnabledResponse\x12t\n\x17SetManualControlEnabled\x12+.kachaka_api.SetManualControlEnabledRequest\x1a,.kachaka_api.SetManualControlEnabledResponse\x12`\n\x17GetManualControlEnabled\x12\x17.kachaka_api.GetRequest\x1a,.kachaka_api.GetManualControlEnabledResponse\x12_\n\x10SetRobotVelocity\x12$.kachaka_api.SetRobotVelocityRequest\x1a%.kachaka_api.SetRobotVelocityResponse\x12\x46\n\nGetMapList\x12\x17.kachaka_api.GetRequest\x1a\x1f.kachaka_api.GetMapListResponse\x12P\n\x0fGetCurrentMapId\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetCurrentMapIdResponse\x12Y\n\x0eLoadMapPreview\x12\".kachaka_api.LoadMapPreviewRequest\x1a#.kachaka_api.LoadMapPreviewResponse\x12L\n\tExportMap\x12\x1d.kachaka_api.ExportMapRequest\x1a\x1e.kachaka_api.ExportMapResponse0\x01\x12L\n\tImportMap\x12\x1d.kachaka_api.ImportMapRequest\x1a\x1e.kachaka_api.ImportMapResponse(\x01\x12N\n\x0eGetHistoryList\x12\x17.kachaka_api.GetRequest\x1a#.kachaka_api.GetHistoryListResponse\x12V\n\x12GetStaticTransform\x12\x17.kachaka_api.GetRequest\x1a\'.kachaka_api.GetStaticTransformResponse\x12\\\n\x13GetDynamicTransform\x12\x19.kachaka_api.EmptyRequest\x1a(.kachaka_api.GetDynamicTransformResponse0\x01\x62\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11kachaka-api.proto\x12\x0bkachaka_api\"\x1a\n\x08Metadata\x12\x0e\n\x06\x63ursor\x18\x01 \x01(\x10\"-\n\x06Result\x12\x0f\n\x07success\x18\x01 \x01(\x08\x12\x12\n\nerror_code\x18\x03 \x01(\x05\"\x1b\n\x05\x45rror\x12\x12\n\nerror_code\x18\x02 \x01(\x05\"1\n\tRosHeader\x12\x12\n\nstamp_nsec\x18\x01 \x01(\x03\x12\x10\n\x08\x66rame_id\x18\x02 \x01(\t\"+\n\x04Pose\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\r\n\x05theta\x18\x03 \x01(\x01\"*\n\x07Vector3\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"8\n\nQuaternion\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"^\n\x06Pose3d\x12&\n\x08position\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12,\n\x0borientation\x18\x02 \x01(\x0b\x32\x17.kachaka_api.Quaternion\"T\n\x05Twist\x12$\n\x06linear\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12%\n\x07\x61ngular\x18\x02 \x01(\x0b\x32\x14.kachaka_api.Vector3\"M\n\x14Pose3dWithCovariance\x12!\n\x04pose\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Pose3d\x12\x12\n\ncovariance\x18\x02 \x03(\x01\"L\n\x13TwistWithCovariance\x12!\n\x05twist\x18\x01 \x01(\x0b\x32\x12.kachaka_api.Twist\x12\x12\n\ncovariance\x18\x02 \x03(\x01\"w\n\x03Map\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x12\n\nresolution\x18\x03 \x01(\x01\x12\r\n\x05width\x18\x04 \x01(\x05\x12\x0e\n\x06height\x18\x05 \x01(\x05\x12!\n\x06origin\x18\x06 \x01(\x0b\x32\x11.kachaka_api.Pose\"\xe0\x01\n\x08Location\x12\n\n\x02id\x18\x01 \x01(\t\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x1f\n\x04pose\x18\x03 \x01(\x0b\x32\x11.kachaka_api.Pose\x12\'\n\x04type\x18\x04 \x01(\x0e\x32\x19.kachaka_api.LocationType\x12%\n\x1dundock_shelf_aligning_to_wall\x18\x05 \x01(\x08\x12\'\n\x1fundock_shelf_avoiding_obstacles\x18\x06 \x01(\x08\x12 \n\x18ignore_voice_recognition\x18\x07 \x01(\x08\"9\n\tShelfSize\x12\r\n\x05width\x18\x01 \x01(\x01\x12\r\n\x05\x64\x65pth\x18\x02 \x01(\x01\x12\x0e\n\x06height\x18\x03 \x01(\x01\"3\n\x10RecognizableName\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x11\n\tdeletable\x18\x02 \x01(\x08\"\xc2\x02\n\x05Shelf\x12\n\n\x02id\x18\x01 \x01(\t\x12\x0c\n\x04name\x18\x02 \x01(\t\x12\x1f\n\x04pose\x18\x03 \x01(\x0b\x32\x11.kachaka_api.Pose\x12$\n\x04size\x18\x04 \x01(\x0b\x32\x16.kachaka_api.ShelfSize\x12\x30\n\nappearance\x18\x05 \x01(\x0e\x32\x1c.kachaka_api.ShelfAppearance\x12\x39\n\x12recognizable_names\x18\x07 \x03(\x0b\x32\x1d.kachaka_api.RecognizableName\x12\x18\n\x10home_location_id\x18\x08 \x01(\t\x12/\n\nspeed_mode\x18\t \x01(\x0e\x32\x1b.kachaka_api.ShelfSpeedMode\x12 \n\x18ignore_voice_recognition\x18\n \x01(\x08\"\xae\x02\n\x06RosImu\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12,\n\x0borientation\x18\x02 \x01(\x0b\x32\x17.kachaka_api.Quaternion\x12\x1e\n\x16orientation_covariance\x18\x03 \x03(\x01\x12.\n\x10\x61ngular_velocity\x18\x04 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12#\n\x1b\x61ngular_velocity_covariance\x18\x05 \x03(\x01\x12\x31\n\x13linear_acceleration\x18\x06 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12&\n\x1elinear_acceleration_covariance\x18\x07 \x03(\x01\"\xaf\x01\n\x0bRosOdometry\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x16\n\x0e\x63hild_frame_id\x18\x02 \x01(\t\x12/\n\x04pose\x18\x03 \x01(\x0b\x32!.kachaka_api.Pose3dWithCovariance\x12/\n\x05twist\x18\x04 \x01(\x0b\x32 .kachaka_api.TwistWithCovariance\"\xeb\x01\n\x0cRosLaserScan\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x11\n\tangle_min\x18\x02 \x01(\x01\x12\x11\n\tangle_max\x18\x03 \x01(\x01\x12\x17\n\x0f\x61ngle_increment\x18\x04 \x01(\x01\x12\x16\n\x0etime_increment\x18\x05 \x01(\x01\x12\x11\n\tscan_time\x18\x06 \x01(\x01\x12\x11\n\trange_min\x18\x07 \x01(\x01\x12\x11\n\trange_max\x18\x08 \x01(\x01\x12\x0e\n\x06ranges\x18\t \x03(\x01\x12\x13\n\x0bintensities\x18\n \x03(\x01\"i\n\x10RegionOfInterest\x12\x10\n\x08x_offset\x18\x01 \x01(\r\x12\x10\n\x08y_offset\x18\x02 \x01(\r\x12\x0e\n\x06height\x18\x03 \x01(\r\x12\r\n\x05width\x18\x04 \x01(\r\x12\x12\n\ndo_rectify\x18\x05 \x01(\x08\"\xee\x01\n\rRosCameraInfo\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06height\x18\x02 \x01(\r\x12\r\n\x05width\x18\x03 \x01(\r\x12\x18\n\x10\x64istortion_model\x18\x04 \x01(\t\x12\t\n\x01\x44\x18\x05 \x03(\x01\x12\t\n\x01K\x18\x06 \x03(\x01\x12\t\n\x01R\x18\x07 \x03(\x01\x12\t\n\x01P\x18\x08 \x03(\x01\x12\x11\n\tbinning_x\x18\t \x01(\r\x12\x11\n\tbinning_y\x18\n \x01(\r\x12*\n\x03roi\x18\x0b \x01(\x0b\x32\x1d.kachaka_api.RegionOfInterest\"\x95\x01\n\x08RosImage\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06height\x18\x02 \x01(\r\x12\r\n\x05width\x18\x03 \x01(\r\x12\x10\n\x08\x65ncoding\x18\x04 \x01(\t\x12\x14\n\x0cis_bigendian\x18\x05 \x01(\x08\x12\x0c\n\x04step\x18\x06 \x01(\r\x12\x0c\n\x04\x64\x61ta\x18\x07 \x01(\x0c\"\xab\x01\n\x13RosTransformStamped\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x16\n\x0e\x63hild_frame_id\x18\x02 \x01(\t\x12)\n\x0btranslation\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Vector3\x12)\n\x08rotation\x18\x04 \x01(\x0b\x32\x17.kachaka_api.Quaternion\"Z\n\x12RosCompressedImage\x12&\n\x06header\x18\x01 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x0e\n\x06\x66ormat\x18\x02 \x01(\t\x12\x0c\n\x04\x64\x61ta\x18\x03 \x01(\x0c\"t\n\x0fObjectDetection\x12\r\n\x05label\x18\x01 \x01(\r\x12*\n\x03roi\x18\x02 \x01(\x0b\x32\x1d.kachaka_api.RegionOfInterest\x12\r\n\x05score\x18\x03 \x01(\x02\x12\x17\n\x0f\x64istance_median\x18\x04 \x01(\x01\"D\n\x17ObjectDetectionFeatures\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05shape\x18\x02 \x03(\r\x12\x0c\n\x04\x64\x61ta\x18\x03 \x03(\x02\"\xbd\x04\n\x07\x43ommand\x12;\n\x12move_shelf_command\x18\x01 \x01(\x0b\x32\x1d.kachaka_api.MoveShelfCommandH\x00\x12?\n\x14return_shelf_command\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.ReturnShelfCommandH\x00\x12?\n\x14undock_shelf_command\x18\x05 \x01(\x0b\x32\x1f.kachaka_api.UndockShelfCommandH\x00\x12\x46\n\x18move_to_location_command\x18\x07 \x01(\x0b\x32\".kachaka_api.MoveToLocationCommandH\x00\x12=\n\x13return_home_command\x18\x08 \x01(\x0b\x32\x1e.kachaka_api.ReturnHomeCommandH\x00\x12;\n\x12\x64ock_shelf_command\x18\t \x01(\x0b\x32\x1d.kachaka_api.DockShelfCommandH\x00\x12\x32\n\rspeak_command\x18\x0c \x01(\x0b\x32\x19.kachaka_api.SpeakCommandH\x00\x12>\n\x14move_to_pose_command\x18\r \x01(\x0b\x32\x1e.kachaka_api.MoveToPoseCommandH\x00\x12\x30\n\x0clock_command\x18\x0f \x01(\x0b\x32\x18.kachaka_api.LockCommandH\x00\x42\t\n\x07\x63ommand\"L\n\x10MoveShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\x12\x1f\n\x17\x64\x65stination_location_id\x18\x02 \x01(\t\"-\n\x12ReturnShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\"-\n\x12UndockShelfCommand\x12\x17\n\x0ftarget_shelf_id\x18\x01 \x01(\t\"3\n\x15MoveToLocationCommand\x12\x1a\n\x12target_location_id\x18\x01 \x01(\t\"\x13\n\x11ReturnHomeCommand\"\x12\n\x10\x44ockShelfCommand\"\x1c\n\x0cSpeakCommand\x12\x0c\n\x04text\x18\x01 \x01(\t\"6\n\x11MoveToPoseCommand\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\x0b\n\x03yaw\x18\x03 \x01(\x01\"#\n\x0bLockCommand\x12\x14\n\x0c\x64uration_sec\x18\x01 \x01(\x01\"\x0e\n\x0c\x45mptyRequest\"5\n\nGetRequest\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\"^\n\x1cGetRobotSerialNumberResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x15\n\rserial_number\x18\x02 \x01(\t\"S\n\x17GetRobotVersionResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07version\x18\x02 \x01(\t\"`\n\x14GetRobotPoseResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x1f\n\x04pose\x18\x02 \x01(\x0b\x32\x11.kachaka_api.Pose\"\x9c\x01\n\x16GetBatteryInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x1c\n\x14remaining_percentage\x18\x02 \x01(\x01\x12;\n\x13power_supply_status\x18\x03 \x01(\x0e\x32\x1e.kachaka_api.PowerSupplyStatus\"[\n\x11GetPngMapResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x1d\n\x03map\x18\x02 \x01(\x0b\x32\x10.kachaka_api.Map\"\x9c\x01\n\x1aGetObjectDetectionResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12&\n\x06header\x18\x02 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12-\n\x07objects\x18\x03 \x03(\x0b\x32\x1c.kachaka_api.ObjectDetection\"\xad\x01\n\"GetObjectDetectionFeaturesResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12&\n\x06header\x18\x02 \x01(\x0b\x32\x16.kachaka_api.RosHeader\x12\x36\n\x08\x66\x65\x61tures\x18\x03 \x03(\x0b\x32$.kachaka_api.ObjectDetectionFeatures\"^\n\x11GetRosImuResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12 \n\x03imu\x18\x02 \x01(\x0b\x32\x13.kachaka_api.RosImu\"m\n\x16GetRosOdometryResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12*\n\x08odometry\x18\x02 \x01(\x0b\x32\x18.kachaka_api.RosOdometry\"k\n\x17GetRosLaserScanResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\'\n\x04scan\x18\x02 \x01(\x0b\x32\x19.kachaka_api.RosLaserScan\"\x7f\n#GetFrontCameraRosCameraInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12/\n\x0b\x63\x61mera_info\x18\x02 \x01(\x0b\x32\x1a.kachaka_api.RosCameraInfo\"o\n\x1eGetFrontCameraRosImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12$\n\x05image\x18\x02 \x01(\x0b\x32\x15.kachaka_api.RosImage\"\x83\x01\n(GetFrontCameraRosCompressedImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12.\n\x05image\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.RosCompressedImage\"~\n\"GetBackCameraRosCameraInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12/\n\x0b\x63\x61mera_info\x18\x02 \x01(\x0b\x32\x1a.kachaka_api.RosCameraInfo\"n\n\x1dGetBackCameraRosImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12$\n\x05image\x18\x02 \x01(\x0b\x32\x15.kachaka_api.RosImage\"\x82\x01\n\'GetBackCameraRosCompressedImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12.\n\x05image\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.RosCompressedImage\"}\n!GetTofCameraRosCameraInfoResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12/\n\x0b\x63\x61mera_info\x18\x02 \x01(\x0b\x32\x1a.kachaka_api.RosCameraInfo\"\x83\x01\n\x1cGetTofCameraRosImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12$\n\x05image\x18\x02 \x01(\x0b\x32\x15.kachaka_api.RosImage\x12\x14\n\x0cis_available\x18\x03 \x01(\x08\"\x97\x01\n&GetTofCameraRosCompressedImageResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12.\n\x05image\x18\x02 \x01(\x0b\x32\x1f.kachaka_api.RosCompressedImage\x12\x14\n\x0cis_available\x18\x03 \x01(\x08\"\x8b\x01\n\x13StartCommandRequest\x12%\n\x07\x63ommand\x18\x01 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncancel_all\x18\x02 \x01(\x08\x12\x16\n\x0etts_on_success\x18\x03 \x01(\t\x12\r\n\x05title\x18\x04 \x01(\t\x12\x12\n\ndeferrable\x18\x05 \x01(\x08\"O\n\x14StartCommandResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x12\n\ncommand_id\x18\x02 \x01(\t\"c\n\x15\x43\x61ncelCommandResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12%\n\x07\x63ommand\x18\x02 \x01(\x0b\x32\x14.kachaka_api.Command\"\xa7\x01\n\x17GetCommandStateResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12(\n\x05state\x18\x02 \x01(\x0e\x32\x19.kachaka_api.CommandState\x12%\n\x07\x63ommand\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncommand_id\x18\x04 \x01(\t\"\xa7\x01\n\x1cGetLastCommandResultResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12#\n\x06result\x18\x02 \x01(\x0b\x32\x13.kachaka_api.Result\x12%\n\x07\x63ommand\x18\x03 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x12\n\ncommand_id\x18\x04 \x01(\t\"6\n\x0fProceedResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"\x86\x01\n\x14GetLocationsResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12(\n\tlocations\x18\x02 \x03(\x0b\x32\x15.kachaka_api.Location\x12\x1b\n\x13\x64\x65\x66\x61ult_location_id\x18\x03 \x01(\t\"b\n\x12GetShelvesResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12#\n\x07shelves\x18\x02 \x03(\x0b\x32\x12.kachaka_api.Shelf\"U\n\x18GetMovingShelfIdResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x10\n\x08shelf_id\x18\x02 \x01(\t\")\n\x15ResetShelfPoseRequest\x12\x10\n\x08shelf_id\x18\x01 \x01(\t\"=\n\x16ResetShelfPoseResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"-\n\x1bSetAutoHomingEnabledRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\"C\n\x1cSetAutoHomingEnabledResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"X\n\x1cGetAutoHomingEnabledResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07\x65nabled\x18\x02 \x01(\x08\"P\n\x1eSetManualControlEnabledRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\x12\x1e\n\x16use_shelf_registration\x18\x02 \x01(\x08\"F\n\x1fSetManualControlEnabledResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"[\n\x1fGetManualControlEnabledResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x0f\n\x07\x65nabled\x18\x02 \x01(\x08\"2\n\x1dSetFrontTorchIntensityRequest\x12\x11\n\tintensity\x18\x01 \x01(\x05\"E\n\x1eSetFrontTorchIntensityResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"1\n\x1cSetBackTorchIntensityRequest\x12\x11\n\tintensity\x18\x01 \x01(\x05\"D\n\x1dSetBackTorchIntensityResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\":\n\x17SetRobotVelocityRequest\x12\x0e\n\x06linear\x18\x01 \x01(\x01\x12\x0f\n\x07\x61ngular\x18\x02 \x01(\x01\"?\n\x18SetRobotVelocityResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"0\n\x18\x41\x63tivateLaserScanRequest\x12\x14\n\x0c\x64uration_sec\x18\x01 \x01(\x01\"@\n\x19\x41\x63tivateLaserScanResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\"{\n\x1aGetStaticTransformResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x34\n\ntransforms\x18\x02 \x03(\x0b\x32 .kachaka_api.RosTransformStamped\"S\n\x1bGetDynamicTransformResponse\x12\x34\n\ntransforms\x18\x01 \x03(\x0b\x32 .kachaka_api.RosTransformStamped\"(\n\x0cMapListEntry\x12\n\n\x02id\x18\x02 \x01(\t\x12\x0c\n\x04name\x18\x01 \x01(\t\"r\n\x12GetMapListResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\x33\n\x10map_list_entries\x18\x02 \x03(\x0b\x32\x19.kachaka_api.MapListEntry\"N\n\x17GetCurrentMapIdResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\n\n\x02id\x18\x02 \x01(\t\"\'\n\x15LoadMapPreviewRequest\x12\x0e\n\x06map_id\x18\x01 \x01(\t\"\\\n\x16LoadMapPreviewResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x1d\n\x03map\x18\x02 \x01(\x0b\x32\x10.kachaka_api.Map\"\"\n\x10\x45xportMapRequest\x12\x0e\n\x06map_id\x18\x01 \x01(\t\"\x83\x02\n\x11\x45xportMapResponse\x12I\n\x10middle_of_stream\x18\x01 \x01(\x0b\x32-.kachaka_api.ExportMapResponse.MiddleOfStreamH\x00\x12\x43\n\rend_of_stream\x18\x02 \x01(\x0b\x32*.kachaka_api.ExportMapResponse.EndOfStreamH\x00\x1a\x1e\n\x0eMiddleOfStream\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\x1a\x32\n\x0b\x45ndOfStream\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.ResultB\n\n\x08response\" \n\x10ImportMapRequest\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\"H\n\x11ImportMapResponse\x12#\n\x06result\x18\x01 \x01(\x0b\x32\x13.kachaka_api.Result\x12\x0e\n\x06map_id\x18\x02 \x01(\t\"\x80\x01\n\x07History\x12\n\n\x02id\x18\x01 \x01(\t\x12%\n\x07\x63ommand\x18\x04 \x01(\x0b\x32\x14.kachaka_api.Command\x12\x0f\n\x07success\x18\x05 \x01(\x08\x12\x12\n\nerror_code\x18\x06 \x01(\x05\x12\x1d\n\x15\x63ommand_executed_time\x18\x07 \x01(\x03\"j\n\x16GetHistoryListResponse\x12\'\n\x08metadata\x18\x01 \x01(\x0b\x32\x15.kachaka_api.Metadata\x12\'\n\thistories\x18\x02 \x03(\x0b\x32\x14.kachaka_api.History*\xc3\x01\n\x11PowerSupplyStatus\x12#\n\x1fPOWER_SUPPLY_STATUS_UNSPECIFIED\x10\x00\x12 \n\x1cPOWER_SUPPLY_STATUS_CHARGING\x10\x01\x12#\n\x1fPOWER_SUPPLY_STATUS_DISCHARGING\x10\x02\x12$\n POWER_SUPPLY_STATUS_NOT_CHARGING\x10\x03\x12\x1c\n\x18POWER_SUPPLY_STATUS_FULL\x10\x04*f\n\x0cLocationType\x12\x1d\n\x19LOCATION_TYPE_UNSPECIFIED\x10\x00\x12\x19\n\x15LOCATION_TYPE_CHARGER\x10\x01\x12\x1c\n\x18LOCATION_TYPE_SHELF_HOME\x10\x02*\xd4\x01\n\x0fShelfAppearance\x12 \n\x1cSHELF_APPEARANCE_UNSPECIFIED\x10\x00\x12\"\n\x1eSHELF_APPEARANCE_DEFAULT_SHELF\x10\x01\x12+\n\'SHELF_APPEARANCE_KACHAKA_SHELF_3DRAWERS\x10\x02\x12+\n\'SHELF_APPEARANCE_KACHAKA_SHELF_2DRAWERS\x10\x03\x12!\n\x1dSHELF_APPEARANCE_KACHAKA_BASE\x10\x08*i\n\x0eShelfSpeedMode\x12 \n\x1cSHELF_SPEED_MODE_UNSPECIFIED\x10\x00\x12\x18\n\x14SHELF_SPEED_MODE_LOW\x10\x01\x12\x1b\n\x17SHELF_SPEED_MODE_NORMAL\x10\x02*\x8d\x01\n\x0bObjectLabel\x12\x1c\n\x18OBJECT_LABEL_UNSPECIFIED\x10\x00\x12\x17\n\x13OBJECT_LABEL_PERSON\x10\x01\x12\x16\n\x12OBJECT_LABEL_SHELF\x10\x02\x12\x18\n\x14OBJECT_LABEL_CHARGER\x10\x03\x12\x15\n\x11OBJECT_LABEL_DOOR\x10\x04*c\n\x0c\x43ommandState\x12\x1d\n\x19\x43OMMAND_STATE_UNSPECIFIED\x10\x00\x12\x19\n\x15\x43OMMAND_STATE_PENDING\x10\x01\x12\x19\n\x15\x43OMMAND_STATE_RUNNING\x10\x02\x32\xa6\x1f\n\nKachakaApi\x12Z\n\x14GetRobotSerialNumber\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetRobotSerialNumberResponse\x12P\n\x0fGetRobotVersion\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetRobotVersionResponse\x12J\n\x0cGetRobotPose\x12\x17.kachaka_api.GetRequest\x1a!.kachaka_api.GetRobotPoseResponse\x12N\n\x0eGetBatteryInfo\x12\x17.kachaka_api.GetRequest\x1a#.kachaka_api.GetBatteryInfoResponse\x12\x44\n\tGetPngMap\x12\x17.kachaka_api.GetRequest\x1a\x1e.kachaka_api.GetPngMapResponse\x12V\n\x12GetObjectDetection\x12\x17.kachaka_api.GetRequest\x1a\'.kachaka_api.GetObjectDetectionResponse\x12\x66\n\x1aGetObjectDetectionFeatures\x12\x17.kachaka_api.GetRequest\x1a/.kachaka_api.GetObjectDetectionFeaturesResponse\x12\x44\n\tGetRosImu\x12\x17.kachaka_api.GetRequest\x1a\x1e.kachaka_api.GetRosImuResponse\x12N\n\x0eGetRosOdometry\x12\x17.kachaka_api.GetRequest\x1a#.kachaka_api.GetRosOdometryResponse\x12P\n\x0fGetRosLaserScan\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetRosLaserScanResponse\x12h\n\x1bGetFrontCameraRosCameraInfo\x12\x17.kachaka_api.GetRequest\x1a\x30.kachaka_api.GetFrontCameraRosCameraInfoResponse\x12^\n\x16GetFrontCameraRosImage\x12\x17.kachaka_api.GetRequest\x1a+.kachaka_api.GetFrontCameraRosImageResponse\x12r\n GetFrontCameraRosCompressedImage\x12\x17.kachaka_api.GetRequest\x1a\x35.kachaka_api.GetFrontCameraRosCompressedImageResponse\x12\x66\n\x1aGetBackCameraRosCameraInfo\x12\x17.kachaka_api.GetRequest\x1a/.kachaka_api.GetBackCameraRosCameraInfoResponse\x12\\\n\x15GetBackCameraRosImage\x12\x17.kachaka_api.GetRequest\x1a*.kachaka_api.GetBackCameraRosImageResponse\x12p\n\x1fGetBackCameraRosCompressedImage\x12\x17.kachaka_api.GetRequest\x1a\x34.kachaka_api.GetBackCameraRosCompressedImageResponse\x12\x64\n\x19GetTofCameraRosCameraInfo\x12\x17.kachaka_api.GetRequest\x1a..kachaka_api.GetTofCameraRosCameraInfoResponse\x12Z\n\x14GetTofCameraRosImage\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetTofCameraRosImageResponse\x12n\n\x1eGetTofCameraRosCompressedImage\x12\x17.kachaka_api.GetRequest\x1a\x33.kachaka_api.GetTofCameraRosCompressedImageResponse\x12S\n\x0cStartCommand\x12 .kachaka_api.StartCommandRequest\x1a!.kachaka_api.StartCommandResponse\x12N\n\rCancelCommand\x12\x19.kachaka_api.EmptyRequest\x1a\".kachaka_api.CancelCommandResponse\x12P\n\x0fGetCommandState\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetCommandStateResponse\x12Z\n\x14GetLastCommandResult\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetLastCommandResultResponse\x12\x42\n\x07Proceed\x12\x19.kachaka_api.EmptyRequest\x1a\x1c.kachaka_api.ProceedResponse\x12J\n\x0cGetLocations\x12\x17.kachaka_api.GetRequest\x1a!.kachaka_api.GetLocationsResponse\x12\x46\n\nGetShelves\x12\x17.kachaka_api.GetRequest\x1a\x1f.kachaka_api.GetShelvesResponse\x12R\n\x10GetMovingShelfId\x12\x17.kachaka_api.GetRequest\x1a%.kachaka_api.GetMovingShelfIdResponse\x12Y\n\x0eResetShelfPose\x12\".kachaka_api.ResetShelfPoseRequest\x1a#.kachaka_api.ResetShelfPoseResponse\x12k\n\x14SetAutoHomingEnabled\x12(.kachaka_api.SetAutoHomingEnabledRequest\x1a).kachaka_api.SetAutoHomingEnabledResponse\x12Z\n\x14GetAutoHomingEnabled\x12\x17.kachaka_api.GetRequest\x1a).kachaka_api.GetAutoHomingEnabledResponse\x12t\n\x17SetManualControlEnabled\x12+.kachaka_api.SetManualControlEnabledRequest\x1a,.kachaka_api.SetManualControlEnabledResponse\x12`\n\x17GetManualControlEnabled\x12\x17.kachaka_api.GetRequest\x1a,.kachaka_api.GetManualControlEnabledResponse\x12q\n\x16SetFrontTorchIntensity\x12*.kachaka_api.SetFrontTorchIntensityRequest\x1a+.kachaka_api.SetFrontTorchIntensityResponse\x12n\n\x15SetBackTorchIntensity\x12).kachaka_api.SetBackTorchIntensityRequest\x1a*.kachaka_api.SetBackTorchIntensityResponse\x12_\n\x10SetRobotVelocity\x12$.kachaka_api.SetRobotVelocityRequest\x1a%.kachaka_api.SetRobotVelocityResponse\x12\x62\n\x11\x41\x63tivateLaserScan\x12%.kachaka_api.ActivateLaserScanRequest\x1a&.kachaka_api.ActivateLaserScanResponse\x12\x46\n\nGetMapList\x12\x17.kachaka_api.GetRequest\x1a\x1f.kachaka_api.GetMapListResponse\x12P\n\x0fGetCurrentMapId\x12\x17.kachaka_api.GetRequest\x1a$.kachaka_api.GetCurrentMapIdResponse\x12Y\n\x0eLoadMapPreview\x12\".kachaka_api.LoadMapPreviewRequest\x1a#.kachaka_api.LoadMapPreviewResponse\x12L\n\tExportMap\x12\x1d.kachaka_api.ExportMapRequest\x1a\x1e.kachaka_api.ExportMapResponse0\x01\x12L\n\tImportMap\x12\x1d.kachaka_api.ImportMapRequest\x1a\x1e.kachaka_api.ImportMapResponse(\x01\x12N\n\x0eGetHistoryList\x12\x17.kachaka_api.GetRequest\x1a#.kachaka_api.GetHistoryListResponse\x12V\n\x12GetStaticTransform\x12\x17.kachaka_api.GetRequest\x1a\'.kachaka_api.GetStaticTransformResponse\x12\\\n\x13GetDynamicTransform\x12\x19.kachaka_api.EmptyRequest\x1a(.kachaka_api.GetDynamicTransformResponse0\x01\x62\x06proto3') _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'kachaka_api_pb2', _globals) if _descriptor._USE_C_DESCRIPTORS == False: DESCRIPTOR._options = None - _globals['_LOCATIONTYPE']._serialized_start=8878 - _globals['_LOCATIONTYPE']._serialized_end=8980 - _globals['_SHELFAPPEARANCE']._serialized_start=8983 - _globals['_SHELFAPPEARANCE']._serialized_end=9195 - _globals['_SHELFSPEEDMODE']._serialized_start=9197 - _globals['_SHELFSPEEDMODE']._serialized_end=9302 - _globals['_OBJECTLABEL']._serialized_start=9305 - _globals['_OBJECTLABEL']._serialized_end=9446 - _globals['_COMMANDSTATE']._serialized_start=9448 - _globals['_COMMANDSTATE']._serialized_end=9547 + _globals['_POWERSUPPLYSTATUS']._serialized_start=9834 + _globals['_POWERSUPPLYSTATUS']._serialized_end=10029 + _globals['_LOCATIONTYPE']._serialized_start=10031 + _globals['_LOCATIONTYPE']._serialized_end=10133 + _globals['_SHELFAPPEARANCE']._serialized_start=10136 + _globals['_SHELFAPPEARANCE']._serialized_end=10348 + _globals['_SHELFSPEEDMODE']._serialized_start=10350 + _globals['_SHELFSPEEDMODE']._serialized_end=10455 + _globals['_OBJECTLABEL']._serialized_start=10458 + _globals['_OBJECTLABEL']._serialized_end=10599 + _globals['_COMMANDSTATE']._serialized_start=10601 + _globals['_COMMANDSTATE']._serialized_end=10700 _globals['_METADATA']._serialized_start=34 _globals['_METADATA']._serialized_end=60 _globals['_RESULT']._serialized_start=62 @@ -113,98 +115,118 @@ _globals['_GETROBOTVERSIONRESPONSE']._serialized_end=4350 _globals['_GETROBOTPOSERESPONSE']._serialized_start=4352 _globals['_GETROBOTPOSERESPONSE']._serialized_end=4448 - _globals['_GETPNGMAPRESPONSE']._serialized_start=4450 - _globals['_GETPNGMAPRESPONSE']._serialized_end=4541 - _globals['_GETOBJECTDETECTIONRESPONSE']._serialized_start=4544 - _globals['_GETOBJECTDETECTIONRESPONSE']._serialized_end=4700 - _globals['_GETOBJECTDETECTIONFEATURESRESPONSE']._serialized_start=4703 - _globals['_GETOBJECTDETECTIONFEATURESRESPONSE']._serialized_end=4876 - _globals['_GETROSIMURESPONSE']._serialized_start=4878 - _globals['_GETROSIMURESPONSE']._serialized_end=4972 - _globals['_GETROSODOMETRYRESPONSE']._serialized_start=4974 - _globals['_GETROSODOMETRYRESPONSE']._serialized_end=5083 - _globals['_GETROSLASERSCANRESPONSE']._serialized_start=5085 - _globals['_GETROSLASERSCANRESPONSE']._serialized_end=5192 - _globals['_GETFRONTCAMERAROSCAMERAINFORESPONSE']._serialized_start=5194 - _globals['_GETFRONTCAMERAROSCAMERAINFORESPONSE']._serialized_end=5321 - _globals['_GETFRONTCAMERAROSIMAGERESPONSE']._serialized_start=5323 - _globals['_GETFRONTCAMERAROSIMAGERESPONSE']._serialized_end=5434 - _globals['_GETFRONTCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_start=5437 - _globals['_GETFRONTCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_end=5568 - _globals['_GETBACKCAMERAROSCAMERAINFORESPONSE']._serialized_start=5570 - _globals['_GETBACKCAMERAROSCAMERAINFORESPONSE']._serialized_end=5696 - _globals['_GETBACKCAMERAROSIMAGERESPONSE']._serialized_start=5698 - _globals['_GETBACKCAMERAROSIMAGERESPONSE']._serialized_end=5808 - _globals['_GETBACKCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_start=5811 - _globals['_GETBACKCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_end=5941 - _globals['_STARTCOMMANDREQUEST']._serialized_start=5943 - _globals['_STARTCOMMANDREQUEST']._serialized_end=6062 - _globals['_STARTCOMMANDRESPONSE']._serialized_start=6064 - _globals['_STARTCOMMANDRESPONSE']._serialized_end=6143 - _globals['_CANCELCOMMANDRESPONSE']._serialized_start=6145 - _globals['_CANCELCOMMANDRESPONSE']._serialized_end=6244 - _globals['_GETCOMMANDSTATERESPONSE']._serialized_start=6247 - _globals['_GETCOMMANDSTATERESPONSE']._serialized_end=6414 - _globals['_GETLASTCOMMANDRESULTRESPONSE']._serialized_start=6417 - _globals['_GETLASTCOMMANDRESULTRESPONSE']._serialized_end=6584 - _globals['_PROCEEDRESPONSE']._serialized_start=6586 - _globals['_PROCEEDRESPONSE']._serialized_end=6640 - _globals['_GETLOCATIONSRESPONSE']._serialized_start=6643 - _globals['_GETLOCATIONSRESPONSE']._serialized_end=6777 - _globals['_GETSHELVESRESPONSE']._serialized_start=6779 - _globals['_GETSHELVESRESPONSE']._serialized_end=6877 - _globals['_GETMOVINGSHELFIDRESPONSE']._serialized_start=6879 - _globals['_GETMOVINGSHELFIDRESPONSE']._serialized_end=6964 - _globals['_RESETSHELFPOSEREQUEST']._serialized_start=6966 - _globals['_RESETSHELFPOSEREQUEST']._serialized_end=7007 - _globals['_RESETSHELFPOSERESPONSE']._serialized_start=7009 - _globals['_RESETSHELFPOSERESPONSE']._serialized_end=7070 - _globals['_SETAUTOHOMINGENABLEDREQUEST']._serialized_start=7072 - _globals['_SETAUTOHOMINGENABLEDREQUEST']._serialized_end=7117 - _globals['_SETAUTOHOMINGENABLEDRESPONSE']._serialized_start=7119 - _globals['_SETAUTOHOMINGENABLEDRESPONSE']._serialized_end=7186 - _globals['_GETAUTOHOMINGENABLEDRESPONSE']._serialized_start=7188 - _globals['_GETAUTOHOMINGENABLEDRESPONSE']._serialized_end=7276 - _globals['_SETMANUALCONTROLENABLEDREQUEST']._serialized_start=7278 - _globals['_SETMANUALCONTROLENABLEDREQUEST']._serialized_end=7358 - _globals['_SETMANUALCONTROLENABLEDRESPONSE']._serialized_start=7360 - _globals['_SETMANUALCONTROLENABLEDRESPONSE']._serialized_end=7430 - _globals['_GETMANUALCONTROLENABLEDRESPONSE']._serialized_start=7432 - _globals['_GETMANUALCONTROLENABLEDRESPONSE']._serialized_end=7523 - _globals['_SETROBOTVELOCITYREQUEST']._serialized_start=7525 - _globals['_SETROBOTVELOCITYREQUEST']._serialized_end=7583 - _globals['_SETROBOTVELOCITYRESPONSE']._serialized_start=7585 - _globals['_SETROBOTVELOCITYRESPONSE']._serialized_end=7648 - _globals['_GETSTATICTRANSFORMRESPONSE']._serialized_start=7650 - _globals['_GETSTATICTRANSFORMRESPONSE']._serialized_end=7773 - _globals['_GETDYNAMICTRANSFORMRESPONSE']._serialized_start=7775 - _globals['_GETDYNAMICTRANSFORMRESPONSE']._serialized_end=7858 - _globals['_MAPLISTENTRY']._serialized_start=7860 - _globals['_MAPLISTENTRY']._serialized_end=7900 - _globals['_GETMAPLISTRESPONSE']._serialized_start=7902 - _globals['_GETMAPLISTRESPONSE']._serialized_end=8016 - _globals['_GETCURRENTMAPIDRESPONSE']._serialized_start=8018 - _globals['_GETCURRENTMAPIDRESPONSE']._serialized_end=8096 - _globals['_LOADMAPPREVIEWREQUEST']._serialized_start=8098 - _globals['_LOADMAPPREVIEWREQUEST']._serialized_end=8137 - _globals['_LOADMAPPREVIEWRESPONSE']._serialized_start=8139 - _globals['_LOADMAPPREVIEWRESPONSE']._serialized_end=8231 - _globals['_EXPORTMAPREQUEST']._serialized_start=8233 - _globals['_EXPORTMAPREQUEST']._serialized_end=8267 - _globals['_EXPORTMAPRESPONSE']._serialized_start=8270 - _globals['_EXPORTMAPRESPONSE']._serialized_end=8529 - _globals['_EXPORTMAPRESPONSE_MIDDLEOFSTREAM']._serialized_start=8435 - _globals['_EXPORTMAPRESPONSE_MIDDLEOFSTREAM']._serialized_end=8465 - _globals['_EXPORTMAPRESPONSE_ENDOFSTREAM']._serialized_start=8467 - _globals['_EXPORTMAPRESPONSE_ENDOFSTREAM']._serialized_end=8517 - _globals['_IMPORTMAPREQUEST']._serialized_start=8531 - _globals['_IMPORTMAPREQUEST']._serialized_end=8563 - _globals['_IMPORTMAPRESPONSE']._serialized_start=8565 - _globals['_IMPORTMAPRESPONSE']._serialized_end=8637 - _globals['_HISTORY']._serialized_start=8640 - _globals['_HISTORY']._serialized_end=8768 - _globals['_GETHISTORYLISTRESPONSE']._serialized_start=8770 - _globals['_GETHISTORYLISTRESPONSE']._serialized_end=8876 - _globals['_KACHAKAAPI']._serialized_start=9550 - _globals['_KACHAKAAPI']._serialized_end=12843 + _globals['_GETBATTERYINFORESPONSE']._serialized_start=4451 + _globals['_GETBATTERYINFORESPONSE']._serialized_end=4607 + _globals['_GETPNGMAPRESPONSE']._serialized_start=4609 + _globals['_GETPNGMAPRESPONSE']._serialized_end=4700 + _globals['_GETOBJECTDETECTIONRESPONSE']._serialized_start=4703 + _globals['_GETOBJECTDETECTIONRESPONSE']._serialized_end=4859 + _globals['_GETOBJECTDETECTIONFEATURESRESPONSE']._serialized_start=4862 + _globals['_GETOBJECTDETECTIONFEATURESRESPONSE']._serialized_end=5035 + _globals['_GETROSIMURESPONSE']._serialized_start=5037 + _globals['_GETROSIMURESPONSE']._serialized_end=5131 + _globals['_GETROSODOMETRYRESPONSE']._serialized_start=5133 + _globals['_GETROSODOMETRYRESPONSE']._serialized_end=5242 + _globals['_GETROSLASERSCANRESPONSE']._serialized_start=5244 + _globals['_GETROSLASERSCANRESPONSE']._serialized_end=5351 + _globals['_GETFRONTCAMERAROSCAMERAINFORESPONSE']._serialized_start=5353 + _globals['_GETFRONTCAMERAROSCAMERAINFORESPONSE']._serialized_end=5480 + _globals['_GETFRONTCAMERAROSIMAGERESPONSE']._serialized_start=5482 + _globals['_GETFRONTCAMERAROSIMAGERESPONSE']._serialized_end=5593 + _globals['_GETFRONTCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_start=5596 + _globals['_GETFRONTCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_end=5727 + _globals['_GETBACKCAMERAROSCAMERAINFORESPONSE']._serialized_start=5729 + _globals['_GETBACKCAMERAROSCAMERAINFORESPONSE']._serialized_end=5855 + _globals['_GETBACKCAMERAROSIMAGERESPONSE']._serialized_start=5857 + _globals['_GETBACKCAMERAROSIMAGERESPONSE']._serialized_end=5967 + _globals['_GETBACKCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_start=5970 + _globals['_GETBACKCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_end=6100 + _globals['_GETTOFCAMERAROSCAMERAINFORESPONSE']._serialized_start=6102 + _globals['_GETTOFCAMERAROSCAMERAINFORESPONSE']._serialized_end=6227 + _globals['_GETTOFCAMERAROSIMAGERESPONSE']._serialized_start=6230 + _globals['_GETTOFCAMERAROSIMAGERESPONSE']._serialized_end=6361 + _globals['_GETTOFCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_start=6364 + _globals['_GETTOFCAMERAROSCOMPRESSEDIMAGERESPONSE']._serialized_end=6515 + _globals['_STARTCOMMANDREQUEST']._serialized_start=6518 + _globals['_STARTCOMMANDREQUEST']._serialized_end=6657 + _globals['_STARTCOMMANDRESPONSE']._serialized_start=6659 + _globals['_STARTCOMMANDRESPONSE']._serialized_end=6738 + _globals['_CANCELCOMMANDRESPONSE']._serialized_start=6740 + _globals['_CANCELCOMMANDRESPONSE']._serialized_end=6839 + _globals['_GETCOMMANDSTATERESPONSE']._serialized_start=6842 + _globals['_GETCOMMANDSTATERESPONSE']._serialized_end=7009 + _globals['_GETLASTCOMMANDRESULTRESPONSE']._serialized_start=7012 + _globals['_GETLASTCOMMANDRESULTRESPONSE']._serialized_end=7179 + _globals['_PROCEEDRESPONSE']._serialized_start=7181 + _globals['_PROCEEDRESPONSE']._serialized_end=7235 + _globals['_GETLOCATIONSRESPONSE']._serialized_start=7238 + _globals['_GETLOCATIONSRESPONSE']._serialized_end=7372 + _globals['_GETSHELVESRESPONSE']._serialized_start=7374 + _globals['_GETSHELVESRESPONSE']._serialized_end=7472 + _globals['_GETMOVINGSHELFIDRESPONSE']._serialized_start=7474 + _globals['_GETMOVINGSHELFIDRESPONSE']._serialized_end=7559 + _globals['_RESETSHELFPOSEREQUEST']._serialized_start=7561 + _globals['_RESETSHELFPOSEREQUEST']._serialized_end=7602 + _globals['_RESETSHELFPOSERESPONSE']._serialized_start=7604 + _globals['_RESETSHELFPOSERESPONSE']._serialized_end=7665 + _globals['_SETAUTOHOMINGENABLEDREQUEST']._serialized_start=7667 + _globals['_SETAUTOHOMINGENABLEDREQUEST']._serialized_end=7712 + _globals['_SETAUTOHOMINGENABLEDRESPONSE']._serialized_start=7714 + _globals['_SETAUTOHOMINGENABLEDRESPONSE']._serialized_end=7781 + _globals['_GETAUTOHOMINGENABLEDRESPONSE']._serialized_start=7783 + _globals['_GETAUTOHOMINGENABLEDRESPONSE']._serialized_end=7871 + _globals['_SETMANUALCONTROLENABLEDREQUEST']._serialized_start=7873 + _globals['_SETMANUALCONTROLENABLEDREQUEST']._serialized_end=7953 + _globals['_SETMANUALCONTROLENABLEDRESPONSE']._serialized_start=7955 + _globals['_SETMANUALCONTROLENABLEDRESPONSE']._serialized_end=8025 + _globals['_GETMANUALCONTROLENABLEDRESPONSE']._serialized_start=8027 + _globals['_GETMANUALCONTROLENABLEDRESPONSE']._serialized_end=8118 + _globals['_SETFRONTTORCHINTENSITYREQUEST']._serialized_start=8120 + _globals['_SETFRONTTORCHINTENSITYREQUEST']._serialized_end=8170 + _globals['_SETFRONTTORCHINTENSITYRESPONSE']._serialized_start=8172 + _globals['_SETFRONTTORCHINTENSITYRESPONSE']._serialized_end=8241 + _globals['_SETBACKTORCHINTENSITYREQUEST']._serialized_start=8243 + _globals['_SETBACKTORCHINTENSITYREQUEST']._serialized_end=8292 + _globals['_SETBACKTORCHINTENSITYRESPONSE']._serialized_start=8294 + _globals['_SETBACKTORCHINTENSITYRESPONSE']._serialized_end=8362 + _globals['_SETROBOTVELOCITYREQUEST']._serialized_start=8364 + _globals['_SETROBOTVELOCITYREQUEST']._serialized_end=8422 + _globals['_SETROBOTVELOCITYRESPONSE']._serialized_start=8424 + _globals['_SETROBOTVELOCITYRESPONSE']._serialized_end=8487 + _globals['_ACTIVATELASERSCANREQUEST']._serialized_start=8489 + _globals['_ACTIVATELASERSCANREQUEST']._serialized_end=8537 + _globals['_ACTIVATELASERSCANRESPONSE']._serialized_start=8539 + _globals['_ACTIVATELASERSCANRESPONSE']._serialized_end=8603 + _globals['_GETSTATICTRANSFORMRESPONSE']._serialized_start=8605 + _globals['_GETSTATICTRANSFORMRESPONSE']._serialized_end=8728 + _globals['_GETDYNAMICTRANSFORMRESPONSE']._serialized_start=8730 + _globals['_GETDYNAMICTRANSFORMRESPONSE']._serialized_end=8813 + _globals['_MAPLISTENTRY']._serialized_start=8815 + _globals['_MAPLISTENTRY']._serialized_end=8855 + _globals['_GETMAPLISTRESPONSE']._serialized_start=8857 + _globals['_GETMAPLISTRESPONSE']._serialized_end=8971 + _globals['_GETCURRENTMAPIDRESPONSE']._serialized_start=8973 + _globals['_GETCURRENTMAPIDRESPONSE']._serialized_end=9051 + _globals['_LOADMAPPREVIEWREQUEST']._serialized_start=9053 + _globals['_LOADMAPPREVIEWREQUEST']._serialized_end=9092 + _globals['_LOADMAPPREVIEWRESPONSE']._serialized_start=9094 + _globals['_LOADMAPPREVIEWRESPONSE']._serialized_end=9186 + _globals['_EXPORTMAPREQUEST']._serialized_start=9188 + _globals['_EXPORTMAPREQUEST']._serialized_end=9222 + _globals['_EXPORTMAPRESPONSE']._serialized_start=9225 + _globals['_EXPORTMAPRESPONSE']._serialized_end=9484 + _globals['_EXPORTMAPRESPONSE_MIDDLEOFSTREAM']._serialized_start=9390 + _globals['_EXPORTMAPRESPONSE_MIDDLEOFSTREAM']._serialized_end=9420 + _globals['_EXPORTMAPRESPONSE_ENDOFSTREAM']._serialized_start=9422 + _globals['_EXPORTMAPRESPONSE_ENDOFSTREAM']._serialized_end=9472 + _globals['_IMPORTMAPREQUEST']._serialized_start=9486 + _globals['_IMPORTMAPREQUEST']._serialized_end=9518 + _globals['_IMPORTMAPRESPONSE']._serialized_start=9520 + _globals['_IMPORTMAPRESPONSE']._serialized_end=9592 + _globals['_HISTORY']._serialized_start=9595 + _globals['_HISTORY']._serialized_end=9723 + _globals['_GETHISTORYLISTRESPONSE']._serialized_start=9725 + _globals['_GETHISTORYLISTRESPONSE']._serialized_end=9831 + _globals['_KACHAKAAPI']._serialized_start=10703 + _globals['_KACHAKAAPI']._serialized_end=14709 # @@protoc_insertion_point(module_scope) diff --git a/python/kachaka_api/generated/kachaka_api_pb2.pyi b/python/kachaka_api/generated/kachaka_api_pb2.pyi index a5749e9..e7896a9 100644 --- a/python/kachaka_api/generated/kachaka_api_pb2.pyi +++ b/python/kachaka_api/generated/kachaka_api_pb2.pyi @@ -6,6 +6,14 @@ from typing import ClassVar as _ClassVar, Iterable as _Iterable, Mapping as _Map DESCRIPTOR: _descriptor.FileDescriptor +class PowerSupplyStatus(int, metaclass=_enum_type_wrapper.EnumTypeWrapper): + __slots__ = () + POWER_SUPPLY_STATUS_UNSPECIFIED: _ClassVar[PowerSupplyStatus] + POWER_SUPPLY_STATUS_CHARGING: _ClassVar[PowerSupplyStatus] + POWER_SUPPLY_STATUS_DISCHARGING: _ClassVar[PowerSupplyStatus] + POWER_SUPPLY_STATUS_NOT_CHARGING: _ClassVar[PowerSupplyStatus] + POWER_SUPPLY_STATUS_FULL: _ClassVar[PowerSupplyStatus] + class LocationType(int, metaclass=_enum_type_wrapper.EnumTypeWrapper): __slots__ = () LOCATION_TYPE_UNSPECIFIED: _ClassVar[LocationType] @@ -39,6 +47,11 @@ class CommandState(int, metaclass=_enum_type_wrapper.EnumTypeWrapper): COMMAND_STATE_UNSPECIFIED: _ClassVar[CommandState] COMMAND_STATE_PENDING: _ClassVar[CommandState] COMMAND_STATE_RUNNING: _ClassVar[CommandState] +POWER_SUPPLY_STATUS_UNSPECIFIED: PowerSupplyStatus +POWER_SUPPLY_STATUS_CHARGING: PowerSupplyStatus +POWER_SUPPLY_STATUS_DISCHARGING: PowerSupplyStatus +POWER_SUPPLY_STATUS_NOT_CHARGING: PowerSupplyStatus +POWER_SUPPLY_STATUS_FULL: PowerSupplyStatus LOCATION_TYPE_UNSPECIFIED: LocationType LOCATION_TYPE_CHARGER: LocationType LOCATION_TYPE_SHELF_HOME: LocationType @@ -493,6 +506,16 @@ class GetRobotPoseResponse(_message.Message): pose: Pose def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., pose: _Optional[_Union[Pose, _Mapping]] = ...) -> None: ... +class GetBatteryInfoResponse(_message.Message): + __slots__ = ("metadata", "remaining_percentage", "power_supply_status") + METADATA_FIELD_NUMBER: _ClassVar[int] + REMAINING_PERCENTAGE_FIELD_NUMBER: _ClassVar[int] + POWER_SUPPLY_STATUS_FIELD_NUMBER: _ClassVar[int] + metadata: Metadata + remaining_percentage: float + power_supply_status: PowerSupplyStatus + def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., remaining_percentage: _Optional[float] = ..., power_supply_status: _Optional[_Union[PowerSupplyStatus, str]] = ...) -> None: ... + class GetPngMapResponse(_message.Message): __slots__ = ("metadata", "map") METADATA_FIELD_NUMBER: _ClassVar[int] @@ -593,17 +616,47 @@ class GetBackCameraRosCompressedImageResponse(_message.Message): image: RosCompressedImage def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., image: _Optional[_Union[RosCompressedImage, _Mapping]] = ...) -> None: ... +class GetTofCameraRosCameraInfoResponse(_message.Message): + __slots__ = ("metadata", "camera_info") + METADATA_FIELD_NUMBER: _ClassVar[int] + CAMERA_INFO_FIELD_NUMBER: _ClassVar[int] + metadata: Metadata + camera_info: RosCameraInfo + def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., camera_info: _Optional[_Union[RosCameraInfo, _Mapping]] = ...) -> None: ... + +class GetTofCameraRosImageResponse(_message.Message): + __slots__ = ("metadata", "image", "is_available") + METADATA_FIELD_NUMBER: _ClassVar[int] + IMAGE_FIELD_NUMBER: _ClassVar[int] + IS_AVAILABLE_FIELD_NUMBER: _ClassVar[int] + metadata: Metadata + image: RosImage + is_available: bool + def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., image: _Optional[_Union[RosImage, _Mapping]] = ..., is_available: bool = ...) -> None: ... + +class GetTofCameraRosCompressedImageResponse(_message.Message): + __slots__ = ("metadata", "image", "is_available") + METADATA_FIELD_NUMBER: _ClassVar[int] + IMAGE_FIELD_NUMBER: _ClassVar[int] + IS_AVAILABLE_FIELD_NUMBER: _ClassVar[int] + metadata: Metadata + image: RosCompressedImage + is_available: bool + def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., image: _Optional[_Union[RosCompressedImage, _Mapping]] = ..., is_available: bool = ...) -> None: ... + class StartCommandRequest(_message.Message): - __slots__ = ("command", "cancel_all", "tts_on_success", "title") + __slots__ = ("command", "cancel_all", "tts_on_success", "title", "deferrable") COMMAND_FIELD_NUMBER: _ClassVar[int] CANCEL_ALL_FIELD_NUMBER: _ClassVar[int] TTS_ON_SUCCESS_FIELD_NUMBER: _ClassVar[int] TITLE_FIELD_NUMBER: _ClassVar[int] + DEFERRABLE_FIELD_NUMBER: _ClassVar[int] command: Command cancel_all: bool tts_on_success: str title: str - def __init__(self, command: _Optional[_Union[Command, _Mapping]] = ..., cancel_all: bool = ..., tts_on_success: _Optional[str] = ..., title: _Optional[str] = ...) -> None: ... + deferrable: bool + def __init__(self, command: _Optional[_Union[Command, _Mapping]] = ..., cancel_all: bool = ..., tts_on_success: _Optional[str] = ..., title: _Optional[str] = ..., deferrable: bool = ...) -> None: ... class StartCommandResponse(_message.Message): __slots__ = ("result", "command_id") @@ -731,6 +784,30 @@ class GetManualControlEnabledResponse(_message.Message): enabled: bool def __init__(self, metadata: _Optional[_Union[Metadata, _Mapping]] = ..., enabled: bool = ...) -> None: ... +class SetFrontTorchIntensityRequest(_message.Message): + __slots__ = ("intensity",) + INTENSITY_FIELD_NUMBER: _ClassVar[int] + intensity: int + def __init__(self, intensity: _Optional[int] = ...) -> None: ... + +class SetFrontTorchIntensityResponse(_message.Message): + __slots__ = ("result",) + RESULT_FIELD_NUMBER: _ClassVar[int] + result: Result + def __init__(self, result: _Optional[_Union[Result, _Mapping]] = ...) -> None: ... + +class SetBackTorchIntensityRequest(_message.Message): + __slots__ = ("intensity",) + INTENSITY_FIELD_NUMBER: _ClassVar[int] + intensity: int + def __init__(self, intensity: _Optional[int] = ...) -> None: ... + +class SetBackTorchIntensityResponse(_message.Message): + __slots__ = ("result",) + RESULT_FIELD_NUMBER: _ClassVar[int] + result: Result + def __init__(self, result: _Optional[_Union[Result, _Mapping]] = ...) -> None: ... + class SetRobotVelocityRequest(_message.Message): __slots__ = ("linear", "angular") LINEAR_FIELD_NUMBER: _ClassVar[int] @@ -745,6 +822,18 @@ class SetRobotVelocityResponse(_message.Message): result: Result def __init__(self, result: _Optional[_Union[Result, _Mapping]] = ...) -> None: ... +class ActivateLaserScanRequest(_message.Message): + __slots__ = ("duration_sec",) + DURATION_SEC_FIELD_NUMBER: _ClassVar[int] + duration_sec: float + def __init__(self, duration_sec: _Optional[float] = ...) -> None: ... + +class ActivateLaserScanResponse(_message.Message): + __slots__ = ("result",) + RESULT_FIELD_NUMBER: _ClassVar[int] + result: Result + def __init__(self, result: _Optional[_Union[Result, _Mapping]] = ...) -> None: ... + class GetStaticTransformResponse(_message.Message): __slots__ = ("metadata", "transforms") METADATA_FIELD_NUMBER: _ClassVar[int] diff --git a/python/kachaka_api/generated/kachaka_api_pb2_grpc.py b/python/kachaka_api/generated/kachaka_api_pb2_grpc.py index a6005b0..07b20ec 100644 --- a/python/kachaka_api/generated/kachaka_api_pb2_grpc.py +++ b/python/kachaka_api/generated/kachaka_api_pb2_grpc.py @@ -30,6 +30,11 @@ def __init__(self, channel: grpc.Channel): request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, response_deserializer=kachaka__api__pb2.GetRobotPoseResponse.FromString, ) + self.GetBatteryInfo = channel.unary_unary( + '/kachaka_api.KachakaApi/GetBatteryInfo', + request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.GetBatteryInfoResponse.FromString, + ) self.GetPngMap = channel.unary_unary( '/kachaka_api.KachakaApi/GetPngMap', request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, @@ -90,6 +95,21 @@ def __init__(self, channel: grpc.Channel): request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, response_deserializer=kachaka__api__pb2.GetBackCameraRosCompressedImageResponse.FromString, ) + self.GetTofCameraRosCameraInfo = channel.unary_unary( + '/kachaka_api.KachakaApi/GetTofCameraRosCameraInfo', + request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.GetTofCameraRosCameraInfoResponse.FromString, + ) + self.GetTofCameraRosImage = channel.unary_unary( + '/kachaka_api.KachakaApi/GetTofCameraRosImage', + request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.GetTofCameraRosImageResponse.FromString, + ) + self.GetTofCameraRosCompressedImage = channel.unary_unary( + '/kachaka_api.KachakaApi/GetTofCameraRosCompressedImage', + request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.GetTofCameraRosCompressedImageResponse.FromString, + ) self.StartCommand = channel.unary_unary( '/kachaka_api.KachakaApi/StartCommand', request_serializer=kachaka__api__pb2.StartCommandRequest.SerializeToString, @@ -155,11 +175,26 @@ def __init__(self, channel: grpc.Channel): request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, response_deserializer=kachaka__api__pb2.GetManualControlEnabledResponse.FromString, ) + self.SetFrontTorchIntensity = channel.unary_unary( + '/kachaka_api.KachakaApi/SetFrontTorchIntensity', + request_serializer=kachaka__api__pb2.SetFrontTorchIntensityRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.SetFrontTorchIntensityResponse.FromString, + ) + self.SetBackTorchIntensity = channel.unary_unary( + '/kachaka_api.KachakaApi/SetBackTorchIntensity', + request_serializer=kachaka__api__pb2.SetBackTorchIntensityRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.SetBackTorchIntensityResponse.FromString, + ) self.SetRobotVelocity = channel.unary_unary( '/kachaka_api.KachakaApi/SetRobotVelocity', request_serializer=kachaka__api__pb2.SetRobotVelocityRequest.SerializeToString, response_deserializer=kachaka__api__pb2.SetRobotVelocityResponse.FromString, ) + self.ActivateLaserScan = channel.unary_unary( + '/kachaka_api.KachakaApi/ActivateLaserScan', + request_serializer=kachaka__api__pb2.ActivateLaserScanRequest.SerializeToString, + response_deserializer=kachaka__api__pb2.ActivateLaserScanResponse.FromString, + ) self.GetMapList = channel.unary_unary( '/kachaka_api.KachakaApi/GetMapList', request_serializer=kachaka__api__pb2.GetRequest.SerializeToString, @@ -224,6 +259,12 @@ def GetRobotPose(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def GetBatteryInfo(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def GetPngMap(self, request, context): """Missing associated documentation comment in .proto file.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) @@ -296,6 +337,24 @@ def GetBackCameraRosCompressedImage(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def GetTofCameraRosCameraInfo(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def GetTofCameraRosImage(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def GetTofCameraRosCompressedImage(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def StartCommand(self, request, context): """Missing associated documentation comment in .proto file.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) @@ -374,12 +433,30 @@ def GetManualControlEnabled(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def SetFrontTorchIntensity(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def SetBackTorchIntensity(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def SetRobotVelocity(self, request, context): """Missing associated documentation comment in .proto file.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def ActivateLaserScan(self, request, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def GetMapList(self, request, context): """Missing associated documentation comment in .proto file.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) @@ -446,6 +523,11 @@ def add_KachakaApiServicer_to_server(servicer, server): request_deserializer=kachaka__api__pb2.GetRequest.FromString, response_serializer=kachaka__api__pb2.GetRobotPoseResponse.SerializeToString, ), + 'GetBatteryInfo': grpc.unary_unary_rpc_method_handler( + servicer.GetBatteryInfo, + request_deserializer=kachaka__api__pb2.GetRequest.FromString, + response_serializer=kachaka__api__pb2.GetBatteryInfoResponse.SerializeToString, + ), 'GetPngMap': grpc.unary_unary_rpc_method_handler( servicer.GetPngMap, request_deserializer=kachaka__api__pb2.GetRequest.FromString, @@ -506,6 +588,21 @@ def add_KachakaApiServicer_to_server(servicer, server): request_deserializer=kachaka__api__pb2.GetRequest.FromString, response_serializer=kachaka__api__pb2.GetBackCameraRosCompressedImageResponse.SerializeToString, ), + 'GetTofCameraRosCameraInfo': grpc.unary_unary_rpc_method_handler( + servicer.GetTofCameraRosCameraInfo, + request_deserializer=kachaka__api__pb2.GetRequest.FromString, + response_serializer=kachaka__api__pb2.GetTofCameraRosCameraInfoResponse.SerializeToString, + ), + 'GetTofCameraRosImage': grpc.unary_unary_rpc_method_handler( + servicer.GetTofCameraRosImage, + request_deserializer=kachaka__api__pb2.GetRequest.FromString, + response_serializer=kachaka__api__pb2.GetTofCameraRosImageResponse.SerializeToString, + ), + 'GetTofCameraRosCompressedImage': grpc.unary_unary_rpc_method_handler( + servicer.GetTofCameraRosCompressedImage, + request_deserializer=kachaka__api__pb2.GetRequest.FromString, + response_serializer=kachaka__api__pb2.GetTofCameraRosCompressedImageResponse.SerializeToString, + ), 'StartCommand': grpc.unary_unary_rpc_method_handler( servicer.StartCommand, request_deserializer=kachaka__api__pb2.StartCommandRequest.FromString, @@ -571,11 +668,26 @@ def add_KachakaApiServicer_to_server(servicer, server): request_deserializer=kachaka__api__pb2.GetRequest.FromString, response_serializer=kachaka__api__pb2.GetManualControlEnabledResponse.SerializeToString, ), + 'SetFrontTorchIntensity': grpc.unary_unary_rpc_method_handler( + servicer.SetFrontTorchIntensity, + request_deserializer=kachaka__api__pb2.SetFrontTorchIntensityRequest.FromString, + response_serializer=kachaka__api__pb2.SetFrontTorchIntensityResponse.SerializeToString, + ), + 'SetBackTorchIntensity': grpc.unary_unary_rpc_method_handler( + servicer.SetBackTorchIntensity, + request_deserializer=kachaka__api__pb2.SetBackTorchIntensityRequest.FromString, + response_serializer=kachaka__api__pb2.SetBackTorchIntensityResponse.SerializeToString, + ), 'SetRobotVelocity': grpc.unary_unary_rpc_method_handler( servicer.SetRobotVelocity, request_deserializer=kachaka__api__pb2.SetRobotVelocityRequest.FromString, response_serializer=kachaka__api__pb2.SetRobotVelocityResponse.SerializeToString, ), + 'ActivateLaserScan': grpc.unary_unary_rpc_method_handler( + servicer.ActivateLaserScan, + request_deserializer=kachaka__api__pb2.ActivateLaserScanRequest.FromString, + response_serializer=kachaka__api__pb2.ActivateLaserScanResponse.SerializeToString, + ), 'GetMapList': grpc.unary_unary_rpc_method_handler( servicer.GetMapList, request_deserializer=kachaka__api__pb2.GetRequest.FromString, @@ -678,6 +790,23 @@ def GetRobotPose(request, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def GetBatteryInfo(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/GetBatteryInfo', + kachaka__api__pb2.GetRequest.SerializeToString, + kachaka__api__pb2.GetBatteryInfoResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def GetPngMap(request, target, @@ -882,6 +1011,57 @@ def GetBackCameraRosCompressedImage(request, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def GetTofCameraRosCameraInfo(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/GetTofCameraRosCameraInfo', + kachaka__api__pb2.GetRequest.SerializeToString, + kachaka__api__pb2.GetTofCameraRosCameraInfoResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def GetTofCameraRosImage(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/GetTofCameraRosImage', + kachaka__api__pb2.GetRequest.SerializeToString, + kachaka__api__pb2.GetTofCameraRosImageResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def GetTofCameraRosCompressedImage(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/GetTofCameraRosCompressedImage', + kachaka__api__pb2.GetRequest.SerializeToString, + kachaka__api__pb2.GetTofCameraRosCompressedImageResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def StartCommand(request, target, @@ -1103,6 +1283,40 @@ def GetManualControlEnabled(request, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def SetFrontTorchIntensity(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/SetFrontTorchIntensity', + kachaka__api__pb2.SetFrontTorchIntensityRequest.SerializeToString, + kachaka__api__pb2.SetFrontTorchIntensityResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def SetBackTorchIntensity(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/SetBackTorchIntensity', + kachaka__api__pb2.SetBackTorchIntensityRequest.SerializeToString, + kachaka__api__pb2.SetBackTorchIntensityResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def SetRobotVelocity(request, target, @@ -1120,6 +1334,23 @@ def SetRobotVelocity(request, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def ActivateLaserScan(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/kachaka_api.KachakaApi/ActivateLaserScan', + kachaka__api__pb2.ActivateLaserScanRequest.SerializeToString, + kachaka__api__pb2.ActivateLaserScanResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def GetMapList(request, target, diff --git a/python/kachaka_api/util/vision.py b/python/kachaka_api/util/vision.py index 656871c..6389486 100644 --- a/python/kachaka_api/util/vision.py +++ b/python/kachaka_api/util/vision.py @@ -1,16 +1,58 @@ +import contextlib import io -from typing import List +import threading +from typing import Generator, List, Optional +import grpc import numpy as np from google._upb._message import RepeatedCompositeContainer from PIL import Image, ImageDraw, ImageFont from ..generated import kachaka_api_pb2 as pb2 +from ..generated.kachaka_api_pb2_grpc import KachakaApiStub OBJECT_LABEL = ["?", "person", "shelf", "charger", "door"] OBJECT_LABEL_COLOR = ["pink", "green", "blue", "cyan", "red"] +class LaserScanActivator: + def __init__(self, target: str = "100.94.1.1:26400") -> None: + self._stub = KachakaApiStub(grpc.insecure_channel(target)) + self._thread: Optional[threading.Thread] = None + self._disposing = threading.Event() + + @contextlib.contextmanager + def activate(self) -> Generator[None, None, None]: + try: + self._start() + yield + except Exception as e: + raise e + finally: + self._stop() + + def _activation_loop( + self, + duration_sec: float = 5.0, + publish_rate: float = 1.0, + ) -> None: + request = pb2.ActivateLaserScanRequest(duration_sec=duration_sec) + wait_timeout = 1 / publish_rate + while not self._disposing.is_set(): + self._stub.ActivateLaserScan(request) + self._disposing.wait(timeout=wait_timeout) + + def _stop(self) -> None: + if self._thread: + self._disposing.set() + self._thread.join() + + def _start(self) -> None: + self._disposing.clear() + self._thread = threading.Thread(target=self._activation_loop) + self._thread.start() + + def get_bbox_drawn_image( image: pb2.RosImage, objects: RepeatedCompositeContainer ) -> Image.Image: diff --git a/ros2/kachaka_description/config/kachaka.rviz b/ros2/kachaka_description/config/kachaka.rviz index f30d74f..e569cfd 100644 --- a/ros2/kachaka_description/config/kachaka.rviz +++ b/ros2/kachaka_description/config/kachaka.rviz @@ -13,8 +13,9 @@ Panels: - /LaserScan1/Topic1 - /FrontCamera1/Topic1 - /BackCamera1/Topic1 + - /TofCamera1/Topic1 Splitter Ratio: 0.5568862557411194 - Tree Height: 843 + Tree Height: 572 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -131,18 +132,32 @@ Visualization Manager: All Enabled: true L01: Value: true - L02: - Value: true - L03: - Value: true L04: Value: true L05: Value: true + L06: + Value: true + L07: + Value: true + L08: + Value: true + L09: + Value: true + L10: + Value: true + L11: + Value: true + L12: + Value: true + L13: + Value: true S01: Value: true S01_home: Value: true + __CHARGER__: + Value: true base_footprint: Value: true base_l_drive_wheel_link: @@ -169,6 +184,8 @@ Visualization Manager: Value: true laser_frame: Value: true + laser_link: + Value: true layout_offset: Value: true lidar_center_frame: @@ -194,14 +211,26 @@ Visualization Manager: map: L01: {} - L02: - {} - L03: - {} L04: {} L05: {} + L06: + {} + L07: + {} + L08: + {} + L09: + {} + L10: + {} + L11: + {} + L12: + {} + L13: + {} S01: {} S01_home: @@ -210,7 +239,8 @@ Visualization Manager: {} layout_offset: home: - {} + __CHARGER__: + {} odom: base_footprint: base_link: @@ -228,9 +258,10 @@ Visualization Manager: {} imu_link: {} - laser_frame: - lidar_center_frame: - {} + laser_link: + laser_frame: + lidar_center_frame: + {} tof_link: tof_camera: {} @@ -323,6 +354,20 @@ Visualization Manager: Reliability Policy: Best Effort Value: /kachaka/back_camera/image_raw/compressed Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: TofCamera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /kachaka/tof_camera/image_raw + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -396,18 +441,20 @@ Window Geometry: collapsed: false FrontCamera: collapsed: false - Height: 1762 + Height: 1376 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000400000000000001f700000646fc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000003b90000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001600460072006f006e007400430061006d0065007200610100000433000001380000004a00fffffffb0000000c00430061006d0065007200610100000521000001930000000000000000fb0000000a0049006d006100670065010000052b000001890000000000000000fb00000014004200610063006b00430061006d00650072006101000005770000013d0000004a00ffffff000000010000015f00000646fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000006e000006460000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000bd00000005afc0100000002fb0000000800540069006d0065000000000000000bd00000058100fffffffb0000000800540069006d00650100000000000004500000000000000000000006a60000064600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f700000506fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000279000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001600460072006f006e007400430061006d00650072006101000002bc000000cf0000002800fffffffb0000000c00430061006d0065007200610100000521000001930000000000000000fb0000000a0049006d006100670065010000052b000001890000000000000000fb00000014004200610063006b00430061006d0065007200610100000391000000d40000002800fffffffb000000120054006f006600430061006d006500720061010000046b000000d80000002800ffffff000000010000015f00000646fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000006e00000646000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000bd00000005afc0100000002fb0000000800540069006d0065000000000000000bd0000002fb00fffffffb0000000800540069006d00650100000000000004500000000000000000000008030000050600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false + TofCamera: + collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 2217 + Width: 2560 X: 0 - Y: 54 + Y: 27 diff --git a/ros2/kachaka_grpc_ros2_bridge/CMakeLists.txt b/ros2/kachaka_grpc_ros2_bridge/CMakeLists.txt index 1eb76e7..ca1016c 100644 --- a/ros2/kachaka_grpc_ros2_bridge/CMakeLists.txt +++ b/ros2/kachaka_grpc_ros2_bridge/CMakeLists.txt @@ -45,6 +45,8 @@ ament_auto_add_library( src/component/odometry_component.cpp src/component/robot_info_component.cpp src/component/static_tf_component.cpp + src/component/tof_camera_component.cpp + src/component/torch_component.cpp src/converter/kachaka_command.cpp src/converter/ros_header.cpp src/dynamic_tf_bridge.cpp @@ -143,6 +145,20 @@ rclcpp_components_register_node( EXECUTABLE odometry) +rclcpp_components_register_node( + ${PROJECT_NAME} + PLUGIN + "kachaka::grpc_ros2_bridge::TofCameraComponent" + EXECUTABLE + tof_camera) + +rclcpp_components_register_node( + ${PROJECT_NAME} + PLUGIN + "kachaka::grpc_ros2_bridge::TorchComponent" + EXECUTABLE + torch) + rclcpp_components_register_node( ${PROJECT_NAME} PLUGIN diff --git a/ros2/kachaka_grpc_ros2_bridge/launch/grpc_ros2_bridge.launch.xml b/ros2/kachaka_grpc_ros2_bridge/launch/grpc_ros2_bridge.launch.xml index f529422..99a0bf0 100644 --- a/ros2/kachaka_grpc_ros2_bridge/launch/grpc_ros2_bridge.launch.xml +++ b/ros2/kachaka_grpc_ros2_bridge/launch/grpc_ros2_bridge.launch.xml @@ -124,6 +124,24 @@ + + + + + + + + stub, rclcpp::Node* node, + bool is_depth, typename GrpcBridge::GrpcService camera_info_service, @@ -75,10 +76,14 @@ class CameraBridge { image_bridge_->StartAsync(); // compressed image + std::string compressed_image_topic = "~/image_raw/compressed"; + if (is_depth) { + compressed_image_topic += "Depth"; + } compressed_image_bridge_ = std::make_unique>( - node, compressed_image_service, "~/image_raw/compressed", qos); + node, compressed_image_service, compressed_image_topic, qos); compressed_image_bridge_->SetConverter( [this](const GetCompressedImageResponse& grpc_msg, sensor_msgs::msg::CompressedImage* ros2_msg) { diff --git a/ros2/kachaka_grpc_ros2_bridge/src/component/back_camera_component.cpp b/ros2/kachaka_grpc_ros2_bridge/src/component/back_camera_component.cpp index b081914..922b488 100644 --- a/ros2/kachaka_grpc_ros2_bridge/src/component/back_camera_component.cpp +++ b/ros2/kachaka_grpc_ros2_bridge/src/component/back_camera_component.cpp @@ -31,7 +31,7 @@ class BackCameraComponent : public rclcpp::Node { CameraBridge>( - stub_, this, + stub_, this, false, std::bind(&kachaka_api::KachakaApi::Stub::GetBackCameraRosCameraInfo, *stub_, _1, _2, _3), std::bind(&kachaka_api::KachakaApi::Stub::GetBackCameraRosImage, *stub_, diff --git a/ros2/kachaka_grpc_ros2_bridge/src/component/front_camera_component.cpp b/ros2/kachaka_grpc_ros2_bridge/src/component/front_camera_component.cpp index ad6f591..28d418c 100644 --- a/ros2/kachaka_grpc_ros2_bridge/src/component/front_camera_component.cpp +++ b/ros2/kachaka_grpc_ros2_bridge/src/component/front_camera_component.cpp @@ -31,7 +31,7 @@ class FrontCameraComponent : public rclcpp::Node { CameraBridge>( - stub_, this, + stub_, this, false, std::bind(&kachaka_api::KachakaApi::Stub::GetFrontCameraRosCameraInfo, *stub_, _1, _2, _3), std::bind(&kachaka_api::KachakaApi::Stub::GetFrontCameraRosImage, diff --git a/ros2/kachaka_grpc_ros2_bridge/src/component/tof_camera_component.cpp b/ros2/kachaka_grpc_ros2_bridge/src/component/tof_camera_component.cpp new file mode 100644 index 0000000..91968d8 --- /dev/null +++ b/ros2/kachaka_grpc_ros2_bridge/src/component/tof_camera_component.cpp @@ -0,0 +1,60 @@ +// Copyright 2023 Preferred Robotics, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// http://www.apache.org/licenses/LICENSE-2.0 +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +#include "../camera_bridge.hpp" +#include "kachaka-api.grpc.pb.h" + +namespace kachaka::grpc_ros2_bridge { + +class TofCameraComponent : public rclcpp::Node { + public: + explicit TofCameraComponent(const rclcpp::NodeOptions& options) + : Node("tof_camera", options) { + stub_ = GetSharedStub(declare_parameter("server_uri", "")); + using namespace std::placeholders; + tof_camera_bridge_ = std::make_unique< + CameraBridge>( + stub_, this, true, + std::bind(&kachaka_api::KachakaApi::Stub::GetTofCameraRosCameraInfo, + *stub_, _1, _2, _3), + std::bind(&kachaka_api::KachakaApi::Stub::GetTofCameraRosImage, *stub_, + _1, _2, _3), + std::bind( + &kachaka_api::KachakaApi::Stub::GetTofCameraRosCompressedImage, + *stub_, _1, _2, _3)); + } + + ~TofCameraComponent() = default; + + TofCameraComponent(const TofCameraComponent&) = delete; + TofCameraComponent& operator=(const TofCameraComponent&) = delete; + + private: + std::shared_ptr stub_{nullptr}; + std::unique_ptr< + CameraBridge> + tof_camera_bridge_; +}; + +} // namespace kachaka::grpc_ros2_bridge + +RCLCPP_COMPONENTS_REGISTER_NODE(kachaka::grpc_ros2_bridge::TofCameraComponent) diff --git a/ros2/kachaka_grpc_ros2_bridge/src/component/torch_component.cpp b/ros2/kachaka_grpc_ros2_bridge/src/component/torch_component.cpp new file mode 100644 index 0000000..b085375 --- /dev/null +++ b/ros2/kachaka_grpc_ros2_bridge/src/component/torch_component.cpp @@ -0,0 +1,101 @@ +// Copyright 2023 Preferred Robotics, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// http://www.apache.org/licenses/LICENSE-2.0 +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "../error_code.hpp" +#include "../grpc_bridge.hpp" +#include "../ros2_topic_bridge.hpp" +#include "../stub_util.hpp" +#include "kachaka-api.grpc.pb.h" + +namespace kachaka::grpc_ros2_bridge { + +class TorchComponent : public rclcpp::Node { + public: + explicit TorchComponent(const rclcpp::NodeOptions& options) + : Node("torch", options) { + stub_ = GetSharedStub(declare_parameter("server_uri", "")); + + rclcpp::QoS qos(rclcpp::KeepLast{1}); + qos.transient_local(); + using namespace std::placeholders; + set_front_torch_intensity_bridge_ = std::make_unique< + GrpcBridge>( + this, std::bind(&kachaka_api::KachakaApi::Stub::SetFrontTorchIntensity, + *stub_, _1, _2, _3)); + set_back_torch_intensity_bridge_ = std::make_unique< + GrpcBridge>( + this, std::bind(&kachaka_api::KachakaApi::Stub::SetBackTorchIntensity, + *stub_, _1, _2, _3)); + front_torch_intensity_subscriber_ = + create_subscription( + "~/front", 1, [this](const std_msgs::msg::UInt8::SharedPtr msg) { + TorchIntensityCallback(true, msg); + }); + back_torch_intensity_subscriber_ = + create_subscription( + "~/back", 1, [this](const std_msgs::msg::UInt8::SharedPtr msg) { + TorchIntensityCallback(false, msg); + }); + } + ~TorchComponent() override = default; + + TorchComponent(const TorchComponent&) = delete; + TorchComponent& operator=(const TorchComponent&) = delete; + + private: + void TorchIntensityCallback(const bool is_front, + const std_msgs::msg::UInt8::SharedPtr msg) { + if (is_front) { + kachaka_api::SetFrontTorchIntensityRequest request; + request.set_intensity(static_cast(msg->data)); + kachaka_api::SetFrontTorchIntensityResponse response; + set_front_torch_intensity_bridge_->CallSync(request, &response); + } else { + kachaka_api::SetBackTorchIntensityRequest request; + request.set_intensity(static_cast(msg->data)); + kachaka_api::SetBackTorchIntensityResponse response; + set_back_torch_intensity_bridge_->CallSync(request, &response); + } + } + + std::shared_ptr stub_{nullptr}; + rclcpp::Subscription::SharedPtr + front_torch_intensity_subscriber_{nullptr}; + rclcpp::Subscription::SharedPtr + back_torch_intensity_subscriber_{nullptr}; + std::unique_ptr> + set_front_torch_intensity_bridge_; + std::unique_ptr> + set_back_torch_intensity_bridge_; +}; + +} // namespace kachaka::grpc_ros2_bridge + +RCLCPP_COMPONENTS_REGISTER_NODE(kachaka::grpc_ros2_bridge::TorchComponent)