|
| 1 | +// Copyright 2025 ROBOTIS CO., LTD. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +// |
| 15 | +// Author: Hyungyu Kim |
| 16 | + |
| 17 | +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ |
| 18 | +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ |
| 19 | + |
| 20 | +#include <variant> |
| 21 | +#include <stdexcept> |
| 22 | +#include <string> |
| 23 | + |
| 24 | +namespace dynamixel |
| 25 | +{ |
| 26 | +enum class DxlError |
| 27 | +{ |
| 28 | + SDK_COMM_SUCCESS = 0, // tx or rx packet communication success |
| 29 | + SDK_COMM_PORT_BUSY = -1000, // Port is busy (in use) |
| 30 | + SDK_COMM_TX_FAIL = -1001, // Failed transmit instruction packet |
| 31 | + SDK_COMM_RX_FAIL = -1002, // Failed get status packet |
| 32 | + SDK_COMM_TX_ERROR = -2000, // Incorrect instruction packet |
| 33 | + SDK_COMM_RX_WAITING = -3000, // Now receiving status packet |
| 34 | + SDK_COMM_RX_TIMEOUT = -3001, // There is no status packet |
| 35 | + SDK_COMM_RX_CORRUPT = -3002, // Incorrect status packet |
| 36 | + SDK_COMM_NOT_AVAILABLE = -9000, |
| 37 | + SDK_ERRNUM_RESULT_FAIL = 1, // Failed to process the instruction packet. |
| 38 | + SDK_ERRNUM_INSTRUCTION = 2, // Instruction error |
| 39 | + SDK_ERRNUM_CRC = 3, // CRC check error |
| 40 | + SDK_ERRNUM_DATA_RANGE = 4, // Data range error |
| 41 | + SDK_ERRNUM_DATA_LENGTH = 5, // Data length error |
| 42 | + SDK_ERRNUM_DATA_LIMIT = 6, // Data limit error |
| 43 | + SDK_ERRNUM_ACCESS = 7, // Access error |
| 44 | + EASY_SDK_FUNCTION_NOT_SUPPORTED = 11, // API does not support this function |
| 45 | + EASY_SDK_MOTOR_TORQUE_OFF = 12, // Motor torque is off |
| 46 | + EASY_SDK_OPERATING_MODE_MISMATCH = 13, // Operating mode is not appropriate for this function |
| 47 | + EASY_SDK_ADD_PARAM_FAIL = 21, // Failed to add parameter |
| 48 | + EASY_SDK_COMMAND_IS_EMPTY = 22, // No command to execute |
| 49 | + EASY_SDK_DUPLICATE_ID = 23, // Duplicate ID in staged commands |
| 50 | + EASY_SDK_FAIL_TO_GET_DATA = 24 // Failed to get data from motor |
| 51 | +}; |
| 52 | + |
| 53 | +template<typename T, typename E> |
| 54 | +class Result |
| 55 | +{ |
| 56 | +private: |
| 57 | + std::variant<T, E> result; |
| 58 | + |
| 59 | +public: |
| 60 | + Result() = default; |
| 61 | + Result(const T & return_value) |
| 62 | + : result(return_value) |
| 63 | + {} |
| 64 | + |
| 65 | + Result(const E & error) |
| 66 | + : result(error) |
| 67 | + {} |
| 68 | + |
| 69 | + bool isSuccess() const |
| 70 | + { |
| 71 | + return std::holds_alternative<T>(result); |
| 72 | + } |
| 73 | + |
| 74 | + T & value() |
| 75 | + { |
| 76 | + if (!isSuccess()) {throw std::logic_error("Result has no value.");} |
| 77 | + return std::get<T>(result); |
| 78 | + } |
| 79 | + const T & value() const |
| 80 | + { |
| 81 | + if (!isSuccess()) {throw std::logic_error("Result has no value.");} |
| 82 | + return std::get<T>(result); |
| 83 | + } |
| 84 | + |
| 85 | + E & error() |
| 86 | + { |
| 87 | + if (isSuccess()) {throw std::logic_error("Result has no error.");} |
| 88 | + return std::get<E>(result); |
| 89 | + } |
| 90 | + |
| 91 | + const E & error() const |
| 92 | + { |
| 93 | + if (isSuccess()) {throw std::logic_error("Result has no error.");} |
| 94 | + return std::get<E>(result); |
| 95 | + } |
| 96 | +}; |
| 97 | + |
| 98 | +template<typename E> |
| 99 | +class Result<void, E> |
| 100 | +{ |
| 101 | +private: |
| 102 | + std::variant<std::monostate, E> result; |
| 103 | + |
| 104 | +public: |
| 105 | + Result() |
| 106 | + : result(std::monostate{}) |
| 107 | + {} |
| 108 | + |
| 109 | + Result(const E & error) |
| 110 | + : result(error) |
| 111 | + {} |
| 112 | + |
| 113 | + bool isSuccess() const |
| 114 | + { |
| 115 | + return std::holds_alternative<std::monostate>(result); |
| 116 | + } |
| 117 | + |
| 118 | + E & error() |
| 119 | + { |
| 120 | + if (!std::holds_alternative<E>(result)) { |
| 121 | + throw std::logic_error("Result has no error."); |
| 122 | + } |
| 123 | + return std::get<E>(result); |
| 124 | + } |
| 125 | + |
| 126 | + const E & error() const |
| 127 | + { |
| 128 | + if (!std::holds_alternative<E>(result)) { |
| 129 | + throw std::logic_error("Result has no error."); |
| 130 | + } |
| 131 | + return std::get<E>(result); |
| 132 | + } |
| 133 | +}; |
| 134 | + |
| 135 | +class DxlRuntimeError : public std::runtime_error |
| 136 | +{ |
| 137 | +public: |
| 138 | + explicit DxlRuntimeError(const std::string & message) |
| 139 | + : std::runtime_error(message) {} |
| 140 | +}; |
| 141 | + |
| 142 | +std::string getErrorMessage(DxlError error_code); |
| 143 | +} // namespace dynamixel |
| 144 | + |
| 145 | +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ */ |
0 commit comments