diff --git a/.github/workflows/ros-ci.yml b/.github/workflows/ros-ci.yml index ec270b15d..f9a4153f5 100644 --- a/.github/workflows/ros-ci.yml +++ b/.github/workflows/ros-ci.yml @@ -4,9 +4,9 @@ name: CI # Specifies the events that trigger the workflow on: push: - branches: [ main, humble ] + branches: [ main, humble, jazzy ] pull_request: - branches: [ main, humble ] + branches: [ main, humble, jazzy ] # Defines a set of jobs to be run as part of the workflow jobs: diff --git a/Doxyfile b/Doxyfile index 37205c995..e68d41661 100644 --- a/Doxyfile +++ b/Doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "DynamixelSDK c++" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.8.4 +PROJECT_NUMBER = 4.0.0 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a diff --git a/ReleaseNote.md b/ReleaseNote.md index c0db5fe4e..69a89f8d7 100644 --- a/ReleaseNote.md +++ b/ReleaseNote.md @@ -1,5 +1,10 @@ # Dynamixel SDK Release Notes +4.0.0 (2025-10-14) +------------------ +* Update Dynamixel Easy SDK in C++ Linux 64bit +* Contributors: Hyungyu Kim + 3.8.4 (2025-05-28) ------------------ * Deprecate ament_include_dependency usage in CMakeLists.txt diff --git a/c++/build/linux64/Makefile b/c++/build/linux64/Makefile index 12fe82a37..c81d39933 100644 --- a/c++/build/linux64/Makefile +++ b/c++/build/linux64/Makefile @@ -35,10 +35,12 @@ SYMLINK = ln -s MKDIR = mkdir CC = gcc CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) $(FORMAT) -fPIC -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) $(FORMAT) -fPIC -g +CONTROL_TABLE_PATH_FLAG = -DCONTROL_TABLE_PATH=\"$(INSTALL_ROOT)/share/dynamixel_sdk/control_table\" +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) $(FORMAT) -fPIC -g $(CONTROL_TABLE_PATH_FLAG) +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) $(FORMAT) -fPIC -g $(CONTROL_TABLE_PATH_FLAG) FORMAT = -m64 INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +INCLUDES += -I$(DIR_DXL)/include #--------------------------------------------------------------------- # Required external libraries @@ -60,6 +62,11 @@ SOURCES = src/dynamixel_sdk/group_bulk_read.cpp \ src/dynamixel_sdk/protocol1_packet_handler.cpp \ src/dynamixel_sdk/protocol2_packet_handler.cpp \ src/dynamixel_sdk/port_handler_linux.cpp \ + src/dynamixel_easy_sdk/connector.cpp \ + src/dynamixel_easy_sdk/control_table.cpp \ + src/dynamixel_easy_sdk/motor.cpp \ + src/dynamixel_easy_sdk/dynamixel_error.cpp \ + src/dynamixel_easy_sdk/group_executor.cpp OBJECTS=$(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) @@ -89,6 +96,13 @@ install: $(TARGET) @$(CHK_DIR_EXISTS) $(INSTALL_ROOT)/include/dynamixel_sdk || $(MKDIR) $(INSTALL_ROOT)/include/dynamixel_sdk $(CP_ALL) $(DIR_DXL)/include/dynamixel_sdk/* $(INSTALL_ROOT)/include/dynamixel_sdk + @$(CHK_DIR_EXISTS) $(INSTALL_ROOT)/include/dynamixel_easy_sdk || $(MKDIR) $(INSTALL_ROOT)/include/dynamixel_easy_sdk + $(CP_ALL) $(DIR_DXL)/include/dynamixel_easy_sdk/* $(INSTALL_ROOT)/include/dynamixel_easy_sdk + + # copy the control_table directory into the share directory + @$(CHK_DIR_EXISTS) $(INSTALL_ROOT)/share/dynamixel_sdk || $(MKDIR) -p $(INSTALL_ROOT)/share/dynamixel_sdk + $(CP_ALL) $(DIR_DXL)/../control_table $(INSTALL_ROOT)/share/dynamixel_sdk/ + $(LD_CONFIG) uninstall: @@ -99,6 +113,8 @@ uninstall: $(RM) $(INSTALL_ROOT)/include/dynamixel_sdk/dynamixel_sdk.h $(RM_ALL) $(INSTALL_ROOT)/include/dynamixel_sdk/* + $(RM_ALL) $(INSTALL_ROOT)/include/dynamixel_easy_sdk/* + $(RM_ALL) $(INSTALL_ROOT)/share/dynamixel_sdk/control_table reinstall: uninstall install @@ -119,6 +135,9 @@ $(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk/%.c $(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk/%.cpp $(CX) $(CXFLAGS) -c $? -o $@ +$(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_easy_sdk/%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + #--------------------------------------------------------------------- # END OF MAKEFILE #--------------------------------------------------------------------- diff --git a/c++/include/dynamixel_easy_sdk/connector.hpp b/c++/include/dynamixel_easy_sdk/connector.hpp new file mode 100644 index 000000000..7bc28f0ae --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/connector.hpp @@ -0,0 +1,62 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONNECTOR_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONNECTOR_HPP_ + +#include +#include +#include + +#include "dynamixel_sdk/dynamixel_sdk.h" +#include "dynamixel_easy_sdk/dynamixel_error.hpp" +#include "dynamixel_easy_sdk/motor.hpp" +#include "dynamixel_easy_sdk/group_executor.hpp" + +namespace dynamixel +{ +class Connector +{ +public: + Connector(const std::string & port_name, int baud_rate); + + virtual ~Connector(); + + std::unique_ptr createMotor(uint8_t id); + std::vector> createAllMotors(int start_id = 0, int end_id = 252); + std::unique_ptr createGroupExecutor(); + + Result write1ByteData(uint8_t id, uint16_t address, uint8_t value); + Result write2ByteData(uint8_t id, uint16_t address, uint16_t value); + Result write4ByteData(uint8_t id, uint16_t address, uint32_t value); + + Result read1ByteData(uint8_t id, uint16_t address); + Result read2ByteData(uint8_t id, uint16_t address); + Result read4ByteData(uint8_t id, uint16_t address); + + Result reboot(uint8_t id); + Result ping(uint8_t id); + Result factoryReset(uint8_t id, uint8_t option); + + PortHandler * getPortHandler() const {return port_handler_.get();} + PacketHandler * getPacketHandler() const {return packet_handler_;} + +private: + std::unique_ptr port_handler_; + PacketHandler * packet_handler_; +}; +} // namespace dynamixel +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONNECTOR_HPP_ */ diff --git a/c++/include/dynamixel_easy_sdk/control_table.hpp b/c++/include/dynamixel_easy_sdk/control_table.hpp new file mode 100644 index 000000000..a9764e151 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/control_table.hpp @@ -0,0 +1,45 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONTROL_TABLE_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONTROL_TABLE_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "dynamixel_easy_sdk/dynamixel_error.hpp" + +namespace dynamixel +{ +struct ControlTableItem +{ + uint16_t address; + uint8_t size; +}; + +class ControlTable +{ +public: + static const std::map ParsingModelList(); + static const std::string getModelName(uint16_t model_number); + static const std::map & getControlTable(uint16_t model_number); +}; +} // namespace dynamixel +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_CONTROL_TABLE_HPP_ */ diff --git a/c++/include/dynamixel_easy_sdk/dynamixel_easy_sdk.hpp b/c++/include/dynamixel_easy_sdk/dynamixel_easy_sdk.hpp new file mode 100644 index 000000000..38b9a4f36 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/dynamixel_easy_sdk.hpp @@ -0,0 +1,26 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_EASY_SDK_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_EASY_SDK_HPP_ + + +#include "dynamixel_easy_sdk/connector.hpp" +#include "dynamixel_easy_sdk/dynamixel_error.hpp" +#include "dynamixel_easy_sdk/motor.hpp" +#include "dynamixel_easy_sdk/group_executor.hpp" + +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_EASY_SDK_HPP_ */ diff --git a/c++/include/dynamixel_easy_sdk/dynamixel_error.hpp b/c++/include/dynamixel_easy_sdk/dynamixel_error.hpp new file mode 100644 index 000000000..b6665cbf2 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/dynamixel_error.hpp @@ -0,0 +1,145 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ + +#include +#include +#include + +namespace dynamixel +{ +enum class DxlError +{ + SDK_COMM_SUCCESS = 0, // tx or rx packet communication success + SDK_COMM_PORT_BUSY = -1000, // Port is busy (in use) + SDK_COMM_TX_FAIL = -1001, // Failed transmit instruction packet + SDK_COMM_RX_FAIL = -1002, // Failed get status packet + SDK_COMM_TX_ERROR = -2000, // Incorrect instruction packet + SDK_COMM_RX_WAITING = -3000, // Now receiving status packet + SDK_COMM_RX_TIMEOUT = -3001, // There is no status packet + SDK_COMM_RX_CORRUPT = -3002, // Incorrect status packet + SDK_COMM_NOT_AVAILABLE = -9000, + SDK_ERRNUM_RESULT_FAIL = 1, // Failed to process the instruction packet. + SDK_ERRNUM_INSTRUCTION = 2, // Instruction error + SDK_ERRNUM_CRC = 3, // CRC check error + SDK_ERRNUM_DATA_RANGE = 4, // Data range error + SDK_ERRNUM_DATA_LENGTH = 5, // Data length error + SDK_ERRNUM_DATA_LIMIT = 6, // Data limit error + SDK_ERRNUM_ACCESS = 7, // Access error + EASY_SDK_FUNCTION_NOT_SUPPORTED = 11, // API does not support this function + EASY_SDK_MOTOR_TORQUE_OFF = 12, // Motor torque is off + EASY_SDK_OPERATING_MODE_MISMATCH = 13, // Operating mode is not appropriate for this function + EASY_SDK_ADD_PARAM_FAIL = 21, // Failed to add parameter + EASY_SDK_COMMAND_IS_EMPTY = 22, // No command to execute + EASY_SDK_DUPLICATE_ID = 23, // Duplicate ID in staged commands + EASY_SDK_FAIL_TO_GET_DATA = 24 // Failed to get data from motor +}; + +template +class Result +{ +private: + std::variant result; + +public: + Result() = default; + Result(const T & return_value) + : result(return_value) + {} + + Result(const E & error) + : result(error) + {} + + bool isSuccess() const + { + return std::holds_alternative(result); + } + + T & value() + { + if (!isSuccess()) {throw std::logic_error("Result has no value.");} + return std::get(result); + } + const T & value() const + { + if (!isSuccess()) {throw std::logic_error("Result has no value.");} + return std::get(result); + } + + E & error() + { + if (isSuccess()) {throw std::logic_error("Result has no error.");} + return std::get(result); + } + + const E & error() const + { + if (isSuccess()) {throw std::logic_error("Result has no error.");} + return std::get(result); + } +}; + +template +class Result +{ +private: + std::variant result; + +public: + Result() + : result(std::monostate{}) + {} + + Result(const E & error) + : result(error) + {} + + bool isSuccess() const + { + return std::holds_alternative(result); + } + + E & error() + { + if (!std::holds_alternative(result)) { + throw std::logic_error("Result has no error."); + } + return std::get(result); + } + + const E & error() const + { + if (!std::holds_alternative(result)) { + throw std::logic_error("Result has no error."); + } + return std::get(result); + } +}; + +class DxlRuntimeError : public std::runtime_error +{ +public: + explicit DxlRuntimeError(const std::string & message) + : std::runtime_error(message) {} +}; + +std::string getErrorMessage(DxlError error_code); +} // namespace dynamixel + +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_DYNAMIXEL_ERROR_HPP_ */ diff --git a/c++/include/dynamixel_easy_sdk/group_executor.hpp b/c++/include/dynamixel_easy_sdk/group_executor.hpp new file mode 100644 index 000000000..fe1aebf85 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/group_executor.hpp @@ -0,0 +1,71 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_GROUP_EXECUTOR_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_GROUP_EXECUTOR_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "dynamixel_sdk/dynamixel_sdk.h" +#include "dynamixel_easy_sdk/control_table.hpp" +#include "dynamixel_easy_sdk/dynamixel_error.hpp" +#include "dynamixel_easy_sdk/staged_command.hpp" + +namespace dynamixel +{ +class Connector; + +class GroupExecutor +{ +public: + explicit GroupExecutor(Connector * connector); + virtual ~GroupExecutor() = default; + + void addCmd(StagedCommand command); + void addCmd(Result result); + Result executeWrite(); + Result>, DxlError> executeRead(); + std::vector getStagedWriteCommands() const { return staged_write_command_list_; } + std::vector getStagedReadCommands() const { return staged_read_command_list_; } + void clearStagedWriteCommands() { staged_write_command_list_.clear(); } + void clearStagedReadCommands() { staged_read_command_list_.clear(); } + +private: + Result executeSyncWrite(uint16_t address, uint16_t length); + Result executeBulkWrite(); + Result>, DxlError> executeSyncRead( + uint16_t address, + uint16_t length); + Result>, DxlError> executeBulkRead(); + + Connector * connector_; + PortHandler * port_handler_; + PacketHandler * packet_handler_; + + GroupBulkWrite group_bulk_write_; + GroupBulkRead group_bulk_read_; + std::vector staged_write_command_list_; + std::vector staged_read_command_list_; +}; + +} // namespace dynamixel + +#endif // DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_GROUP_EXECUTOR_HPP_ diff --git a/c++/include/dynamixel_easy_sdk/motor.hpp b/c++/include/dynamixel_easy_sdk/motor.hpp new file mode 100644 index 000000000..12b3d7f20 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/motor.hpp @@ -0,0 +1,132 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_MOTOR_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_MOTOR_HPP_ + +#include +#include +#include +#include + +#include "dynamixel_sdk/dynamixel_sdk.h" +#include "dynamixel_easy_sdk/control_table.hpp" +#include "dynamixel_easy_sdk/dynamixel_error.hpp" +#include "dynamixel_easy_sdk/staged_command.hpp" + +namespace dynamixel +{ +class Connector; + +class Motor +{ +public: + enum class OperatingMode + { + CURRENT = 0, + VELOCITY = 1, + POSITION = 3, + EXTENDED_POSITION = 4, + PWM = 16 + }; + + enum class ProfileConfiguration + { + VELOCITY_BASED = 0, + TIME_BASED = 1 + }; + + enum class Direction + { + NORMAL = 0, + REVERSE = 1 + }; + + Motor(uint8_t id, uint16_t model_number, Connector * connector); + + virtual ~Motor(); + + Result enableTorque(); + Result disableTorque(); + Result setGoalPosition(uint32_t position); + Result setGoalVelocity(uint32_t velocity); + Result setGoalCurrent(int16_t current); + Result setGoalPWM(int16_t pwm); + Result LEDOn(); + Result LEDOff(); + + Result ping(); + Result isTorqueOn(); + Result isLEDOn(); + Result getPresentPosition(); + Result getPresentVelocity(); + Result getMaxPositionLimit(); + Result getMinPositionLimit(); + Result getVelocityLimit(); + Result getCurrentLimit(); + Result getPWMLimit(); + Result getOperatingMode(); + + Result changeID(uint8_t new_id); + Result setOperatingMode(OperatingMode mode); + Result setProfileConfiguration(ProfileConfiguration config); + Result setDirection(Direction direction); + Result setPositionPGain(uint16_t p_gain); + Result setPositionIGain(uint16_t i_gain); + Result setPositionDGain(uint16_t d_gain); + Result setVelocityPGain(uint16_t p_gain); + Result setVelocityIGain(uint16_t i_gain); + Result setHomingOffset(int32_t offset); + Result setMaxPositionLimit(uint32_t limit); + Result setMinPositionLimit(uint32_t limit); + Result setVelocityLimit(uint32_t limit); + Result setCurrentLimit(uint16_t limit); + Result setPWMLimit(uint16_t limit); + + Result reboot(); + Result factoryResetAll(); + Result factoryResetExceptID(); + Result factoryResetExceptIDAndBaudRate(); + + Result stageEnableTorque(); + Result stageDisableTorque(); + Result stageSetGoalPosition(uint32_t position); + Result stageSetGoalVelocity(uint32_t velocity); + Result stageLEDOn(); + Result stageLEDOff(); + + Result stageIsTorqueOn(); + Result stageIsLEDOn(); + Result stageGetPresentPosition(); + Result stageGetPresentVelocity(); + + uint8_t getID() const {return id_;} + uint16_t getModelNumber() const {return model_number_;} + std::string getModelName() const {return model_name_;} + +private: + Result getControlTableItem(const std::string & item_name); + uint8_t id_; + uint16_t model_number_; + std::string model_name_; + uint8_t torque_; + uint8_t operating_mode_; + + Connector * connector_; + const std::map & control_table_; +}; +} // namespace dynamixel +#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_MOTOR_HPP_ */ diff --git a/c++/include/dynamixel_easy_sdk/staged_command.hpp b/c++/include/dynamixel_easy_sdk/staged_command.hpp new file mode 100644 index 000000000..43a990495 --- /dev/null +++ b/c++/include/dynamixel_easy_sdk/staged_command.hpp @@ -0,0 +1,54 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_STAGED_COMMAND_HPP_ +#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_STAGED_COMMAND_HPP_ + +#include +#include + +namespace dynamixel +{ +enum class CommandType +{ + WRITE, + READ +}; + +struct StagedCommand +{ + StagedCommand( + CommandType _command_type, + uint8_t _id, + uint16_t _address, + uint16_t _length, + const std::vector & _data) + : command_type(_command_type), + id(_id), + address(_address), + length(_length), + data(_data) {} + + CommandType command_type; + uint8_t id; + uint16_t address; + uint16_t length; + std::vector data; +}; + +} // namespace dynamixel + +#endif // DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_EASY_SDK_STAGED_COMMAND_HPP_ diff --git a/c++/library.properties b/c++/library.properties index c31b0f03c..e0bc01c96 100644 --- a/c++/library.properties +++ b/c++/library.properties @@ -1,5 +1,5 @@ name=DynamixelSDK -version=3.8.3 +version=4.0.0 author=ROBOTIS maintainer=ROBOTIS sentence=DynamixelSDK for Arduino diff --git a/c++/src/dynamixel_easy_sdk/connector.cpp b/c++/src/dynamixel_easy_sdk/connector.cpp new file mode 100644 index 000000000..6c15b1b8b --- /dev/null +++ b/c++/src/dynamixel_easy_sdk/connector.cpp @@ -0,0 +1,218 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#include "dynamixel_easy_sdk/connector.hpp" + +static constexpr float PROTOCOL_VERSION = 2.0f; + +namespace dynamixel +{ +Connector::Connector(const std::string & port_name, int baud_rate) +{ + port_handler_ = std::unique_ptr(PortHandler::getPortHandler(port_name.c_str())); + packet_handler_ = PacketHandler::getPacketHandler(PROTOCOL_VERSION); + + if (!port_handler_->openPort()) { + throw DxlRuntimeError("Failed to open the port!"); + } + + if (!port_handler_->setBaudRate(baud_rate)) { + throw DxlRuntimeError("Failed to set the baud rate!"); + } +} + +Connector::~Connector() +{ + port_handler_->closePort(); +} + +std::unique_ptr Connector::createMotor(uint8_t id) +{ + Result result = ping(id); + if (!result.isSuccess()) { + throw DxlRuntimeError(getErrorMessage(result.error())); + } + return std::make_unique(id, result.value(), this); +} + +std::vector> Connector::createAllMotors(int start_id, int end_id) +{ + if (start_id < 0 || start_id > 252 || end_id < 0 || end_id > 252 || start_id > end_id) { + throw DxlRuntimeError("Invalid ID range. ID should be in the range of 0 to 252."); + } + std::vector ids; + std::vector> motors; + int dxl_comm_result = packet_handler_->broadcastPing(port_handler_.get(), ids); + if (dxl_comm_result != COMM_SUCCESS) { + throw DxlRuntimeError(getErrorMessage(static_cast(dxl_comm_result))); + } + for (auto & id : ids) { + if (id >= start_id && id <= end_id) { + motors.push_back(createMotor(id)); + } + } + return motors; +} + +std::unique_ptr Connector::createGroupExecutor() +{ + return std::make_unique(this); +} + +Result Connector::read1ByteData(uint8_t id, uint16_t address) +{ + uint8_t dxl_error = 0; + uint8_t data = 0; + int dxl_comm_result = packet_handler_->read1ByteTxRx( + port_handler_.get(), + id, address, + &data, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return data; +} + +Result Connector::read2ByteData(uint8_t id, uint16_t address) +{ + uint8_t dxl_error = 0; + uint16_t data = 0; + int dxl_comm_result = packet_handler_->read2ByteTxRx( + port_handler_.get(), + id, address, + &data, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return data; +} + +Result Connector::read4ByteData(uint8_t id, uint16_t address) +{ + uint8_t dxl_error = 0; + uint32_t data = 0; + int dxl_comm_result = packet_handler_->read4ByteTxRx( + port_handler_.get(), + id, address, + &data, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return data; +} + +Result Connector::write1ByteData(uint8_t id, uint16_t address, uint8_t value) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = packet_handler_->write1ByteTxRx( + port_handler_.get(), + id, address, value, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return {}; +} + +Result Connector::write2ByteData(uint8_t id, uint16_t address, uint16_t value) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = packet_handler_->write2ByteTxRx( + port_handler_.get(), + id, address, + value, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return {}; +} + +Result Connector::write4ByteData(uint8_t id, uint16_t address, uint32_t value) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = packet_handler_->write4ByteTxRx( + port_handler_.get(), + id, address, + value, + &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return {}; +} + +Result Connector::reboot(uint8_t id) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = packet_handler_->reboot(port_handler_.get(), id, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return {}; +} + +Result Connector::ping(uint8_t id) +{ + uint8_t dxl_error = 0; + uint16_t data = 0; + int dxl_comm_result = packet_handler_->ping(port_handler_.get(), id, &data, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return data; +} + +Result Connector::factoryReset(uint8_t id, uint8_t option) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = packet_handler_->factoryReset(port_handler_.get(), id, option, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + if (dxl_error != 0) { + return static_cast(dxl_error); + } + return {}; +} +} // namespace dynamixel diff --git a/c++/src/dynamixel_easy_sdk/control_table.cpp b/c++/src/dynamixel_easy_sdk/control_table.cpp new file mode 100644 index 000000000..c94890fed --- /dev/null +++ b/c++/src/dynamixel_easy_sdk/control_table.cpp @@ -0,0 +1,124 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#include + +#include "dynamixel_easy_sdk/control_table.hpp" + +namespace dynamixel +{ +const std::map ControlTable::ParsingModelList() +{ + std::map tmp_model_list; + std::string file_name = std::string(CONTROL_TABLE_PATH) + "/dynamixel.model"; + std::ifstream infile(file_name); + if (!infile.is_open()) { + throw std::runtime_error("Error: Could not open file " + file_name); + } + + std::string line; + std::getline(infile, line); + while (std::getline(infile, line)) { + if (line.empty()) { + continue; + } + std::stringstream ss(line); + std::string name; + std::string number_str; + if (std::getline(ss, number_str, '\t')) { + if (std::getline(ss, name)) { + try { + uint16_t number = std::stoi(number_str); + tmp_model_list[number] = name; + } catch (const std::invalid_argument & e) { + throw std::runtime_error("Invalid model number in " + file_name + ": " + number_str); + } catch (const std::out_of_range & e) { + throw std::runtime_error("Model number out of range in " + file_name + ": " + number_str); + } catch (...) { + throw std::runtime_error("Unknown error while parsing model list in " + file_name); + } + } + } + } + return tmp_model_list; +} + +const std::string ControlTable::getModelName(uint16_t model_number) +{ + static const std::map model_name_list_ = ParsingModelList(); + auto it = model_name_list_.find(model_number); + if (it == model_name_list_.end()) { + throw DxlRuntimeError( + "Model number is not found in dynamixel.model: " + std::to_string(model_number)); + } + return it->second; +} + +const std::map & ControlTable::getControlTable(uint16_t model_number) +{ + static std::map> control_tables_cache_; + if (control_tables_cache_.count(model_number)) { + return control_tables_cache_.at(model_number); + } + + const std::string & model_filename = getModelName(model_number); + std::string full_path = std::string(CONTROL_TABLE_PATH) + "/" + model_filename; + + std::map control_table; + std::ifstream infile(full_path); + + if (!infile.is_open()) { + throw std::runtime_error("Error: Could not open model file: " + full_path); + } + + std::string line; + bool in_section = false; + + while (std::getline(infile, line)) { + if (line.empty()) { + continue; + } + if (line == "[control table]") { + in_section = true; + if (!std::getline(infile, line)) { + break; + } + continue; + } + + if (in_section) { + std::stringstream ss(line); + std::string address_str, size_str, name; + + if (std::getline(ss, address_str, '\t') && + std::getline(ss, size_str, '\t') && + std::getline(ss, name)) + { + try { + ControlTableItem item; + item.address = std::stoi(address_str); + item.size = std::stoi(size_str); + control_table[name] = item; + } catch (const std::exception & e) { + throw std::runtime_error("Error parsing control table item: " + line + " - " + e.what()); + } + } + } + } + auto result = control_tables_cache_.emplace(model_number, std::move(control_table)); + return result.first->second; +} +} // namespace dynamixel diff --git a/c++/src/dynamixel_easy_sdk/dynamixel_error.cpp b/c++/src/dynamixel_easy_sdk/dynamixel_error.cpp new file mode 100644 index 000000000..d90ed6f68 --- /dev/null +++ b/c++/src/dynamixel_easy_sdk/dynamixel_error.cpp @@ -0,0 +1,73 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#include "dynamixel_easy_sdk/dynamixel_error.hpp" + +namespace dynamixel +{ +std::string getErrorMessage(DxlError error_code) +{ + switch (error_code) { + case DxlError::SDK_COMM_SUCCESS: + return "[TxRxResult] Communication success."; + case DxlError::SDK_COMM_PORT_BUSY: + return "[TxRxResult] Port is in use!"; + case DxlError::SDK_COMM_TX_FAIL: + return "[TxRxResult] Failed transmit instruction packet!"; + case DxlError::SDK_COMM_RX_FAIL: + return "[TxRxResult] Failed get status packet from device!"; + case DxlError::SDK_COMM_TX_ERROR: + return "[TxRxResult] Incorrect instruction packet!"; + case DxlError::SDK_COMM_RX_WAITING: + return "[TxRxResult] Now receiving status packet!"; + case DxlError::SDK_COMM_RX_TIMEOUT: + return "[TxRxResult] There is no status packet!"; + case DxlError::SDK_COMM_RX_CORRUPT: + return "[TxRxResult] Incorrect status packet!"; + case DxlError::SDK_COMM_NOT_AVAILABLE: + return "[TxRxResult] Protocol does not support this function!"; + case DxlError::SDK_ERRNUM_RESULT_FAIL: + return "[RxPacketError] Failed to process the instruction packet!"; + case DxlError::SDK_ERRNUM_INSTRUCTION: + return "[RxPacketError] Undefined instruction or incorrect instruction!"; + case DxlError::SDK_ERRNUM_CRC: + return "[RxPacketError] CRC doesn't match!"; + case DxlError::SDK_ERRNUM_DATA_RANGE: + return "[RxPacketError] The data value is out of range!"; + case DxlError::SDK_ERRNUM_DATA_LENGTH: + return "[RxPacketError] The data length does not match as expected!"; + case DxlError::SDK_ERRNUM_DATA_LIMIT: + return "[RxPacketError] The data value exceeds the limit value!"; + case DxlError::SDK_ERRNUM_ACCESS: + return "[RxPacketError] Writing or Reading is not available to target address!"; + case DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED: + return "[EasySDKError] Easy SDK function is not supported on this model!"; + case DxlError::EASY_SDK_MOTOR_TORQUE_OFF: + return "[EasySDKError] Motor torque is off!"; + case DxlError::EASY_SDK_OPERATING_MODE_MISMATCH: + return "[EasySDKError] Operating mode is not appropriate for this function!"; + case DxlError::EASY_SDK_ADD_PARAM_FAIL: + return "[EasySDKError] Failed to add parameter!"; + case DxlError::EASY_SDK_COMMAND_IS_EMPTY: + return "[EasySDKError] No command to execute!"; + case DxlError::EASY_SDK_DUPLICATE_ID: + return "[EasySDKError] Duplicate ID found in staged commands."; + case DxlError::EASY_SDK_FAIL_TO_GET_DATA: + return "[EasySDKError] Failed to get data from motor."; + default: return "Unknown Error"; + } +} +} // namespace dynamixel diff --git a/c++/src/dynamixel_easy_sdk/group_executor.cpp b/c++/src/dynamixel_easy_sdk/group_executor.cpp new file mode 100644 index 000000000..3f9dd7cad --- /dev/null +++ b/c++/src/dynamixel_easy_sdk/group_executor.cpp @@ -0,0 +1,220 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#include + +#include "dynamixel_easy_sdk/group_executor.hpp" +#include "dynamixel_easy_sdk/connector.hpp" + +namespace dynamixel +{ + +GroupExecutor::GroupExecutor(Connector * connector) +: connector_(connector), + port_handler_(connector->getPortHandler()), + packet_handler_(connector->getPacketHandler()), + group_bulk_write_(port_handler_, packet_handler_), + group_bulk_read_(port_handler_, packet_handler_) +{} + +void GroupExecutor::addCmd(StagedCommand command) +{ + if (command.command_type == CommandType::WRITE) { + staged_write_command_list_.push_back(std::move(command)); + } else if (command.command_type == CommandType::READ) { + staged_read_command_list_.push_back(std::move(command)); + } +} + +void GroupExecutor::addCmd(Result result) +{ + if (!result.isSuccess()) { + return; + } + + if (result.value().command_type == CommandType::WRITE) { + staged_write_command_list_.push_back(std::move(result.value())); + } else if (result.value().command_type == CommandType::READ) { + staged_read_command_list_.push_back(std::move(result.value())); + } +} + +Result GroupExecutor::executeWrite() +{ + if (staged_write_command_list_.empty()) { + return DxlError::EASY_SDK_COMMAND_IS_EMPTY; + } + const auto & reference_command = staged_write_command_list_.front(); + bool is_sync = true; + std::vector sorted_list = staged_write_command_list_; + std::sort( + sorted_list.begin(), + sorted_list.end(), + [](const StagedCommand & a, const StagedCommand & b) { + return a.id < b.id; + } + ); + + auto it = std::adjacent_find( + sorted_list.begin(), + sorted_list.end(), + [](const StagedCommand & a, const StagedCommand & b) { + return a.id == b.id; + } + ); + + if (it != sorted_list.end()) { + return DxlError::EASY_SDK_DUPLICATE_ID; + } + + for (size_t i = 1; i < staged_write_command_list_.size(); ++i) { + if (staged_write_command_list_[i].address != reference_command.address || + staged_write_command_list_[i].length != reference_command.length) + { + is_sync = false; + break; + } + } + + Result result; + if (is_sync) { + result = executeSyncWrite(reference_command.address, reference_command.length); + } else { + result = executeBulkWrite(); + } + return result; +} + +Result>, DxlError> GroupExecutor::executeRead() +{ + if (staged_read_command_list_.empty()) { + return DxlError::EASY_SDK_COMMAND_IS_EMPTY; + } + const auto & reference_command = staged_read_command_list_.front(); + bool is_sync = true; + for (size_t i = 1; i < staged_read_command_list_.size(); ++i) { + if (staged_read_command_list_[i].address != reference_command.address || + staged_read_command_list_[i].length != reference_command.length) + { + is_sync = false; + break; + } + } + + Result>, DxlError> result; + if (is_sync) { + result = executeSyncRead(reference_command.address, reference_command.length); + } else { + result = executeBulkRead(); + } + return result; +} + +Result GroupExecutor::executeSyncWrite(uint16_t address, uint16_t length) +{ + GroupSyncWrite group_sync_write(port_handler_, packet_handler_, address, length); + for (auto & command : staged_write_command_list_) { + if (!group_sync_write.addParam(command.id, command.data.data())) { + return DxlError::EASY_SDK_ADD_PARAM_FAIL; + } + } + int dxl_comm_result = group_sync_write.txPacket(); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + return {}; +} + +Result GroupExecutor::executeBulkWrite() +{ + group_bulk_write_.clearParam(); + + for (auto & command : staged_write_command_list_) { + if (!group_bulk_write_.addParam( + command.id, + command.address, + command.length, + command.data.data())) + { + return DxlError::EASY_SDK_ADD_PARAM_FAIL; + } + } + + int dxl_comm_result = group_bulk_write_.txPacket(); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + return {}; +} + +Result>, DxlError> GroupExecutor::executeSyncRead( + uint16_t address, + uint16_t length) +{ + GroupSyncRead group_sync_read(port_handler_, packet_handler_, address, length); + for (const auto & command : staged_read_command_list_) { + if (!group_sync_read.addParam(command.id)) { + return DxlError::EASY_SDK_ADD_PARAM_FAIL; + } + } + + int dxl_comm_result = group_sync_read.txRxPacket(); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + std::vector> result_list; + for (const auto & command : staged_read_command_list_) { + if (!group_sync_read.isAvailable(command.id, address, length)) { + result_list.push_back(DxlError::EASY_SDK_FAIL_TO_GET_DATA); + continue; + } + int32_t value = group_sync_read.getData(command.id, address, length); + result_list.push_back(value); + } + + return result_list; +} + +Result>, DxlError> GroupExecutor::executeBulkRead() +{ + group_bulk_read_.clearParam(); + + for (const auto & command : staged_read_command_list_) { + if (!group_bulk_read_.addParam(command.id, command.address, command.length)) { + return DxlError::EASY_SDK_ADD_PARAM_FAIL; + } + } + + int dxl_comm_result = group_bulk_read_.txRxPacket(); + if (dxl_comm_result != COMM_SUCCESS) { + return static_cast(dxl_comm_result); + } + + std::vector> result_list; + for (const auto & command : staged_read_command_list_) { + if (!group_bulk_read_.isAvailable(command.id, command.address, command.length)) { + result_list.push_back(DxlError::EASY_SDK_FAIL_TO_GET_DATA); + continue; + } + + int32_t value = group_bulk_read_.getData(command.id, command.address, command.length); + result_list.push_back(value); + } + + return result_list; +} + +} // namespace dynamixel diff --git a/c++/src/dynamixel_easy_sdk/motor.cpp b/c++/src/dynamixel_easy_sdk/motor.cpp new file mode 100644 index 000000000..e169a0171 --- /dev/null +++ b/c++/src/dynamixel_easy_sdk/motor.cpp @@ -0,0 +1,711 @@ +// Copyright 2025 ROBOTIS CO., LTD. +// +// 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. +// +// Author: Hyungyu Kim + +#include "dynamixel_easy_sdk/motor.hpp" +#include "dynamixel_easy_sdk/connector.hpp" + +namespace dynamixel +{ +Motor::Motor(uint8_t id, uint16_t model_number, Connector * connector) +: id_(id), + model_number_(model_number), + model_name_(ControlTable::getModelName(model_number)), + connector_(connector), + control_table_(ControlTable::getControlTable(model_number)) +{ + Result torque_result = this->isTorqueOn(); + if (!torque_result.isSuccess()) { + throw DxlRuntimeError("Failed to get torque status: " + getErrorMessage(torque_result.error())); + } + torque_ = torque_result.value(); + + Result mode_result = this->getOperatingMode(); + if (!mode_result.isSuccess()) { + throw DxlRuntimeError("Failed to get operating mode: " + getErrorMessage(mode_result.error())); + } + operating_mode_ = mode_result.value(); +} + +Motor::~Motor() {} + +Result Motor::enableTorque() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write1ByteData(id_, item.address, 1); + return result; +} + +Result Motor::disableTorque() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write1ByteData(id_, item.address, 0); + return result; +} + +Result Motor::setGoalPosition(uint32_t position) +{ + if(torque_ == 0) { + return DxlError::EASY_SDK_MOTOR_TORQUE_OFF; + } + if(operating_mode_ != static_cast(OperatingMode::POSITION)) { + return DxlError::EASY_SDK_OPERATING_MODE_MISMATCH; + } + Result item_result = getControlTableItem("Goal Position"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 4) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write4ByteData(id_, item.address, position); + return result; +} + +Result Motor::setGoalVelocity(uint32_t velocity) +{ + if(torque_ == 0) { + return DxlError::EASY_SDK_MOTOR_TORQUE_OFF; + } + if(operating_mode_ != static_cast(OperatingMode::VELOCITY)) { + return DxlError::EASY_SDK_OPERATING_MODE_MISMATCH; + } + Result item_result = getControlTableItem("Goal Velocity"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 4) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write4ByteData(id_, item.address, velocity); + return result; +} + +Result Motor::setGoalCurrent(int16_t current) +{ + if(torque_ == 0) { + return DxlError::EASY_SDK_MOTOR_TORQUE_OFF; + } + if(operating_mode_ != static_cast(OperatingMode::CURRENT)) { + return DxlError::EASY_SDK_OPERATING_MODE_MISMATCH; + } + Result item_result = getControlTableItem("Goal Current"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, current); + return result; +} + +Result Motor::setGoalPWM(int16_t pwm) +{ + if(torque_ == 0) { + return DxlError::EASY_SDK_MOTOR_TORQUE_OFF; + } + if(operating_mode_ != static_cast(OperatingMode::PWM)) { + return DxlError::EASY_SDK_OPERATING_MODE_MISMATCH; + } + Result item_result = getControlTableItem("Goal PWM"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, pwm); + return result; +} + +Result Motor::LEDOn() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write1ByteData(id_, item.address, 1); + return result; +} + +Result Motor::LEDOff() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write1ByteData(id_, item.address, 0); + return result; +} + +Result Motor::ping() +{ + Result result = connector_->ping(id_); + return result; +} + +Result Motor::isTorqueOn() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read1ByteData(id_, item.address); + return result; +} + +Result Motor::isLEDOn() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read1ByteData(id_, item.address); + return result; +} + +Result Motor::getPresentPosition() +{ + Result item_result = getControlTableItem("Present Position"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read4ByteData(id_, item.address); + if (!result.isSuccess()) { + return result.error(); + } + return static_cast(result.value()); +} + +Result Motor::getPresentVelocity() +{ + Result item_result = getControlTableItem("Present Velocity"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read4ByteData(id_, item.address); + if (!result.isSuccess()) { + return result.error(); + } + return static_cast(result.value()); +} + +Result Motor::getMaxPositionLimit() +{ + Result item_result = getControlTableItem("Max Position Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 4) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->read4ByteData(id_, item.address); + return result; +} + +Result Motor::getMinPositionLimit() +{ + Result item_result = getControlTableItem("Min Position Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 4) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->read4ByteData(id_, item.address); + return result; +} + +Result Motor::getVelocityLimit() +{ + Result item_result = getControlTableItem("Velocity Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 4) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->read4ByteData(id_, item.address); + return result; +} + +Result Motor::getCurrentLimit() +{ + Result item_result = getControlTableItem("Current Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read2ByteData(id_, item.address); + return result; +} + +Result Motor::getPWMLimit() +{ + Result item_result = getControlTableItem("PWM Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read2ByteData(id_, item.address); + return result; +} + +Result Motor::getOperatingMode() +{ + Result item_result = getControlTableItem("Operating Mode"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->read1ByteData(id_, item.address); + return result; +} + +Result Motor::changeID(uint8_t new_id) +{ + Result item_result = getControlTableItem("ID"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write1ByteData(id_, item.address, new_id); + if (result.isSuccess()) { + id_ = new_id; + } + return result; +} + +Result Motor::setOperatingMode(OperatingMode mode) +{ + Result item_result = getControlTableItem("Operating Mode"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + uint8_t mode_value = static_cast(mode); + Result result = connector_->write1ByteData(id_, item.address, mode_value); + if (!result.isSuccess()) { + return result.error(); + } + return result; +} + +Result Motor::setProfileConfiguration(ProfileConfiguration config) +{ + Result item_result = getControlTableItem("Drive Mode"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + auto read_result = connector_->read1ByteData(id_, item.address); + if (!read_result.isSuccess()) { + return read_result.error(); + } + + uint8_t drive_mode = read_result.value(); + const uint8_t PROFILE_BIT_MASK = 0b00000100; + + if (config == ProfileConfiguration::TIME_BASED) { + drive_mode |= PROFILE_BIT_MASK; + } else if (config == ProfileConfiguration::VELOCITY_BASED) { + drive_mode &= ~PROFILE_BIT_MASK; + } + Result result = connector_->write1ByteData(id_, item.address, drive_mode); + return result; +} + +Result Motor::setDirection(Direction direction) +{ + Result item_result = getControlTableItem("Drive Mode"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + auto read_result = connector_->read1ByteData(id_, item.address); + if (!read_result.isSuccess()) { + return read_result.error(); + } + uint8_t drive_mode = read_result.value(); + const uint8_t DIRECTION_BIT_MASK = 0b00000001; + if (direction == Direction::NORMAL) { + drive_mode &= ~DIRECTION_BIT_MASK; + } else if (direction == Direction::REVERSE) { + drive_mode |= DIRECTION_BIT_MASK; + } + Result result = connector_->write1ByteData(id_, item.address, drive_mode); + return result; +} + +Result Motor::setPositionPGain(uint16_t p_gain) +{ + Result item_result = getControlTableItem("Position P Gain"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, p_gain); + return result; +} + +Result Motor::setPositionIGain(uint16_t i_gain) +{ + Result item_result = getControlTableItem("Position I Gain"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, i_gain); + return result; +} + +Result Motor::setPositionDGain(uint16_t d_gain) +{ + Result item_result = getControlTableItem("Position D Gain"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, d_gain); + return result; +} + +Result Motor::setVelocityPGain(uint16_t p_gain) +{ + Result item_result = getControlTableItem("Velocity P Gain"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, p_gain); + return result; +} + +Result Motor::setVelocityIGain(uint16_t i_gain) +{ + Result item_result = getControlTableItem("Velocity I Gain"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + if (item.size != 2) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + Result result = connector_->write2ByteData(id_, item.address, i_gain); + return result; +} + +Result Motor::setHomingOffset(int32_t offset) +{ + Result item_result = getControlTableItem("Homing Offset"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write4ByteData( + id_, + item.address, + static_cast(offset)); + return result; +} + +Result Motor::setMaxPositionLimit(uint32_t limit) +{ + Result item_result = getControlTableItem("Max Position Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write4ByteData(id_, item.address, limit); + return result; +} + +Result Motor::setMinPositionLimit(uint32_t limit) +{ + Result item_result = getControlTableItem("Min Position Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write4ByteData(id_, item.address, limit); + return result; +} + +Result Motor::setVelocityLimit(uint32_t limit) +{ + Result item_result = getControlTableItem("Velocity Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write4ByteData(id_, item.address, limit); + return result; +} + +Result Motor::setCurrentLimit(uint16_t limit) +{ + Result item_result = getControlTableItem("Current Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write2ByteData(id_, item.address, limit); + return result; +} + +Result Motor::setPWMLimit(uint16_t limit) +{ + Result item_result = getControlTableItem("PWM Limit"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + const ControlTableItem & item = item_result.value(); + Result result = connector_->write2ByteData(id_, item.address, limit); + return result; +} + +Result Motor::reboot() +{ + Result result = connector_->reboot(id_); + return result; +} + +Result Motor::factoryResetAll() +{ + Result result = connector_->factoryReset(id_, 0xFF); + return result; +} + +Result Motor::factoryResetExceptID() +{ + Result result = connector_->factoryReset(id_, 0x01); + return result; +} + +Result Motor::factoryResetExceptIDAndBaudRate() +{ + Result result = connector_->factoryReset(id_, 0x02); + return result; +} + +Result Motor::stageEnableTorque() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + {1}); + return cmd; +} + +Result Motor::stageDisableTorque() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + {0}); + return cmd; +} + +Result Motor::stageSetGoalPosition(uint32_t position) +{ + Result item_result = getControlTableItem("Goal Position"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + std::vector data; + for (size_t i = 0; i < item_result.value().size; ++i) { + data.push_back((position >> (8 * i)) & 0xFF); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + data + ); + return cmd; +} + +Result Motor::stageSetGoalVelocity(uint32_t velocity) +{ + Result item_result = getControlTableItem("Goal Velocity"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + std::vector data; + for (size_t i = 0; i < item_result.value().size; ++i) { + data.push_back((velocity >> (8 * i)) & 0xFF); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + data + ); + return cmd; +} + +Result Motor::stageLEDOn() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + {1} + ); + return cmd; +} + +Result Motor::stageLEDOff() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::WRITE, + id_, + item_result.value().address, + item_result.value().size, + {0} + ); + return cmd; +} + +Result Motor::stageIsTorqueOn() +{ + Result item_result = getControlTableItem("Torque Enable"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::READ, + id_, + item_result.value().address, + item_result.value().size, + {} + ); + return cmd; +} + +Result Motor::stageIsLEDOn() +{ + Result item_result = getControlTableItem("LED"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::READ, + id_, + item_result.value().address, + item_result.value().size, + {} + ); + return cmd; +} + +Result Motor::stageGetPresentPosition() +{ + Result item_result = getControlTableItem("Present Position"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::READ, + id_, + item_result.value().address, + item_result.value().size, + {} + ); + return cmd; +} + +Result Motor::stageGetPresentVelocity() +{ + Result item_result = getControlTableItem("Present Velocity"); + if (!item_result.isSuccess()) { + return item_result.error(); + } + StagedCommand cmd( + CommandType::READ, + id_, + item_result.value().address, + item_result.value().size, + {} + ); + return cmd; +} + +Result Motor::getControlTableItem(const std::string & name) +{ + auto it = control_table_.find(name); + if (it == control_table_.end()) { + return DxlError::EASY_SDK_FUNCTION_NOT_SUPPORTED; + } + return it->second; +} +} // namespace dynamixel diff --git a/control_table/2xc430_w250.model b/control_table/2xc430_w250.model new file mode 100644 index 000000000..deb48f6fb --- /dev/null +++ b/control_table/2xc430_w250.model @@ -0,0 +1,70 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/2xl430_w250.model b/control_table/2xl430_w250.model new file mode 100644 index 000000000..deb48f6fb --- /dev/null +++ b/control_table/2xl430_w250.model @@ -0,0 +1,70 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/dynamixel.model b/control_table/dynamixel.model new file mode 100644 index 000000000..2814bee74 --- /dev/null +++ b/control_table/dynamixel.model @@ -0,0 +1,61 @@ +Number Name +30 mx_28.model +311 mx_64.model +321 mx_106.model +350 xl320.model +1000 xh430_w350.model +1001 xd430_t350.model +1010 xh430_w210.model +1011 xd430_t210.model +1020 xm430_w350.model +1030 xm430_w210.model +1040 xh430_v350.model +1050 xh430_v210.model +1060 xl430_w250.model +1070 xc430_w150.model +1080 xc430_w240.model +1090 2xl430_w250.model +1100 xh540_w270.model +1101 xd540_t270.model +1110 xh540_w150.model +1111 xd540_t150.model +1120 xm540_w270.model +1130 xm540_w150.model +1140 xh540_v270.model +1150 xh540_v150.model +1160 2xc430_w250.model +1170 xw540_t260.model +1180 xw540_t140.model +1190 xl330_m077.model +1200 xl330_m288.model +1210 xc330_t181.model +1220 xc330_t288.model +1230 xc330_m181.model +1240 xc330_m288.model +1270 xw430_t333.model +1310 xw540_h260.model +2000 ph42_020_s300.model +2010 ph54_100_s500.model +2020 ph54_200_s500.model +2100 pm42_010_s260.model +2110 pm54_040_s250.model +2120 pm54_060_s250.model +4000 ym070_210_m001.model +4010 ym070_210_b001.model +4020 ym070_210_r051.model +4030 ym070_210_r099.model +4040 ym070_210_a051.model +4050 ym070_210_a099.model +4120 ym080_230_m001.model +4130 ym080_230_b001.model +4140 ym080_230_r051.model +4150 ym080_230_r099.model +4160 ym080_230_a051.model +4170 ym080_230_a099.model +35074 rh_p12_rn.model +43289 m42_10_s260_ra.model +46097 m54_40_s250_ra.model +46353 m54_60_s250_ra.model +51201 h42_20_s300_ra.model +53769 h54_100_s500_ra.model +54025 h54_200_s500_ra.model diff --git a/control_table/h42_20_s300_ra.model b/control_table/h42_20_s300_ra.model new file mode 100644 index 000000000..8dff9987a --- /dev/null +++ b/control_table/h42_20_s300_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 303750 +value_of_min_radian_position -303750 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/h54_100_s500_ra.model b/control_table/h54_100_s500_ra.model new file mode 100644 index 000000000..d75df80b8 --- /dev/null +++ b/control_table/h54_100_s500_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 501923 +value_of_min_radian_position -501923 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/h54_200_s500_ra.model b/control_table/h54_200_s500_ra.model new file mode 100644 index 000000000..d75df80b8 --- /dev/null +++ b/control_table/h54_200_s500_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 501923 +value_of_min_radian_position -501923 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/m42_10_s260_ra.model b/control_table/m42_10_s260_ra.model new file mode 100644 index 000000000..54a22a351 --- /dev/null +++ b/control_table/m42_10_s260_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 263187 +value_of_min_radian_position -263187 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/m54_40_s250_ra.model b/control_table/m54_40_s250_ra.model new file mode 100644 index 000000000..a076cb27c --- /dev/null +++ b/control_table/m54_40_s250_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/m54_60_s250_ra.model b/control_table/m54_60_s250_ra.model new file mode 100644 index 000000000..a076cb27c --- /dev/null +++ b/control_table/m54_60_s250_ra.model @@ -0,0 +1,84 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/mx_106.model b/control_table/mx_106.model new file mode 100644 index 000000000..6bdd26fc0 --- /dev/null +++ b/control_table/mx_106.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/mx_28.model b/control_table/mx_28.model new file mode 100644 index 000000000..05ec3f10a --- /dev/null +++ b/control_table/mx_28.model @@ -0,0 +1,71 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/mx_64.model b/control_table/mx_64.model new file mode 100644 index 000000000..6bdd26fc0 --- /dev/null +++ b/control_table/mx_64.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/ph42_020_s300.model b/control_table/ph42_020_s300.model new file mode 100644 index 000000000..d9dd95273 --- /dev/null +++ b/control_table/ph42_020_s300.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 303750 +value_of_min_radian_position -303750 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ph54_100_s500.model b/control_table/ph54_100_s500.model new file mode 100644 index 000000000..e99523f92 --- /dev/null +++ b/control_table/ph54_100_s500.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 501923 +value_of_min_radian_position -501923 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ph54_200_s500.model b/control_table/ph54_200_s500.model new file mode 100644 index 000000000..e99523f92 --- /dev/null +++ b/control_table/ph54_200_s500.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 501923 +value_of_min_radian_position -501923 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/pm42_010_s260.model b/control_table/pm42_010_s260.model new file mode 100644 index 000000000..1585fb4e4 --- /dev/null +++ b/control_table/pm42_010_s260.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 263187 +value_of_min_radian_position -263187 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/pm54_040_s250.model b/control_table/pm54_040_s250.model new file mode 100644 index 000000000..3f0313461 --- /dev/null +++ b/control_table/pm54_040_s250.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/pm54_060_s250.model b/control_table/pm54_060_s250.model new file mode 100644 index 000000000..3f0313461 --- /dev/null +++ b/control_table/pm54_060_s250.model @@ -0,0 +1,87 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +60 1 Startup Configuration +63 1 Shutdown +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +530 2 Position I Gain +532 2 Position P Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +600 2 External Port Data 1 +602 2 External Port Data 2 +604 2 External Port Data 3 +606 2 External Port Data 4 +878 1 Backup Ready +168 2 Indirect Address 1 +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/rh_p12_rn.model b/control_table/rh_p12_rn.model new file mode 100644 index 000000000..b081fab49 --- /dev/null +++ b/control_table/rh_p12_rn.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 740 +value_of_min_radian_position -740 +min_radian -1.099 +max_radian 1.099 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0119380521 rad/s signed +Goal Velocity 0.0119380521 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +11 1 Operating Mode +12 1 Secondary ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +59 1 External Port Mode 4 +63 1 Shutdown +168 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED Red +514 1 LED Green +515 1 LED Blue +516 1 Status Return Level +517 1 Registered Instruction +518 1 Hardware Error Status +524 2 Velocity I Gain +526 2 Velocity P Gain +528 2 Position D Gain +532 2 Position P Gain +530 2 Position I Gain +536 2 Feedforward 2nd Gain +538 2 Feedforward 1st Gain +546 1 Bus Watchdog +548 2 Goal PWM +550 2 Goal Current +552 4 Goal Velocity +556 4 Profile Acceleration +560 4 Profile Velocity +564 4 Goal Position +568 2 Realtime Tick +570 1 Moving +571 1 Moving Status +572 2 Present PWM +574 2 Present Current +576 4 Present Velocity +580 4 Present Position +584 4 Velocity Trajectory +588 4 Position Trajectory +592 2 Present Input Voltage +594 1 Present Temperature +634 1 Indirect Data 1 +168 2 Indirect Address Write +634 1 Indirect Data Write +296 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/xc330_m181.model b/control_table/xc330_m181.model new file mode 100644 index 000000000..0a0935085 --- /dev/null +++ b/control_table/xc330_m181.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xc330_m181_fw52.model b/control_table/xc330_m181_fw52.model new file mode 100644 index 000000000..d8483c92c --- /dev/null +++ b/control_table/xc330_m181_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xc330_m288.model b/control_table/xc330_m288.model new file mode 100644 index 000000000..0a0935085 --- /dev/null +++ b/control_table/xc330_m288.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xc330_m288_fw52.model b/control_table/xc330_m288_fw52.model new file mode 100644 index 000000000..d8483c92c --- /dev/null +++ b/control_table/xc330_m288_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xc330_t181.model b/control_table/xc330_t181.model new file mode 100644 index 000000000..80ca68db9 --- /dev/null +++ b/control_table/xc330_t181.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 0.0006709470296015791 N/m signed +Goal Current 0.0006709470296015791 N/m signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xc330_t181_fw52.model b/control_table/xc330_t181_fw52.model new file mode 100644 index 000000000..7d397de1d --- /dev/null +++ b/control_table/xc330_t181_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 0.0006709470296015791 N/m signed +Goal Current 0.0006709470296015791 N/m signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xc330_t288.model b/control_table/xc330_t288.model new file mode 100644 index 000000000..a3ba279df --- /dev/null +++ b/control_table/xc330_t288.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 0.0009674796739867748 N/m signed +Goal Current 0.0009674796739867748 N/m signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xc330_t288_fw52.model b/control_table/xc330_t288_fw52.model new file mode 100644 index 000000000..f01d3fe77 --- /dev/null +++ b/control_table/xc330_t288_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 0.0009674796739867748 N/m signed +Goal Current 0.0009674796739867748 N/m signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xc430_w150.model b/control_table/xc430_w150.model new file mode 100644 index 000000000..deb48f6fb --- /dev/null +++ b/control_table/xc430_w150.model @@ -0,0 +1,70 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xc430_w240.model b/control_table/xc430_w240.model new file mode 100644 index 000000000..deb48f6fb --- /dev/null +++ b/control_table/xc430_w240.model @@ -0,0 +1,70 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xd430_t210.model b/control_table/xd430_t210.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xd430_t210.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xd430_t350.model b/control_table/xd430_t350.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xd430_t350.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xd540_t150.model b/control_table/xd540_t150.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xd540_t150.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xd540_t270.model b/control_table/xd540_t270.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xd540_t270.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh430_v210.model b/control_table/xh430_v210.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xh430_v210.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh430_v350.model b/control_table/xh430_v350.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xh430_v350.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh430_w210.model b/control_table/xh430_w210.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xh430_w210.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh430_w350.model b/control_table/xh430_w350.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xh430_w350.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh540_v150.model b/control_table/xh540_v150.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xh540_v150.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh540_v270.model b/control_table/xh540_v270.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xh540_v270.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh540_w150.model b/control_table/xh540_w150.model new file mode 100644 index 000000000..3487436ba --- /dev/null +++ b/control_table/xh540_w150.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 0.0045 N/m signed +Goal Current 0.0045 N/m signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xh540_w270.model b/control_table/xh540_w270.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xh540_w270.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xl320.model b/control_table/xl320.model new file mode 100644 index 000000000..df5914a74 --- /dev/null +++ b/control_table/xl320.model @@ -0,0 +1,46 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0116228475 rad/s signed +Goal Velocity 0.0116228475 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 1 Firmware Version +3 1 ID +4 1 Baud Rate +5 1 Return Delay Time +6 2 CW Angle Limit +8 2 CCW Angle Limit +11 1 Control Mode +12 1 Temperature Limit +13 1 Min Voltage Limit +14 1 Max Voltage Limit +15 2 Max Torque +17 1 Status Return Level +18 1 Shutdown +24 1 Torque Enable +25 1 LED +27 1 D Gain +28 1 I Gain +29 1 P Gain +30 2 Goal Position +32 2 Moving Speed +35 2 Torque Limit +37 2 Present Position +39 2 Present Speed +41 2 Present Load +45 1 Present Voltage +46 1 Present Temperature +47 1 Registered Instruction +49 1 Moving +50 1 Hardware Error Status +51 2 Punch diff --git a/control_table/xl330_m077.model b/control_table/xl330_m077.model new file mode 100644 index 000000000..0a0935085 --- /dev/null +++ b/control_table/xl330_m077.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xl330_m077_fw52.model b/control_table/xl330_m077_fw52.model new file mode 100644 index 000000000..d8483c92c --- /dev/null +++ b/control_table/xl330_m077_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xl330_m288.model b/control_table/xl330_m288.model new file mode 100644 index 000000000..0a0935085 --- /dev/null +++ b/control_table/xl330_m288.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +180 2 Indirect Address Read +230 1 Indirect Data Read diff --git a/control_table/xl330_m288_fw52.model b/control_table/xl330_m288_fw52.model new file mode 100644 index 000000000..d8483c92c --- /dev/null +++ b/control_table/xl330_m288_fw52.model @@ -0,0 +1,75 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +62 1 PWM Slope +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +208 1 Indirect Data 1 +168 2 Indirect Address Write +208 1 Indirect Data Write +180 2 Indirect Address Read +214 1 Indirect Data Read diff --git a/control_table/xl430_w250.model b/control_table/xl430_w250.model new file mode 100644 index 000000000..deb48f6fb --- /dev/null +++ b/control_table/xl430_w250.model @@ -0,0 +1,70 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xm430_w210.model b/control_table/xm430_w210.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xm430_w210.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xm430_w350.model b/control_table/xm430_w350.model new file mode 100644 index 000000000..aa324bb6c --- /dev/null +++ b/control_table/xm430_w350.model @@ -0,0 +1,74 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xm540_w150.model b/control_table/xm540_w150.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xm540_w150.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xm540_w270.model b/control_table/xm540_w270.model new file mode 100644 index 000000000..033c4c871 --- /dev/null +++ b/control_table/xm540_w270.model @@ -0,0 +1,80 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +56 1 External Port Mode 1 +57 1 External Port Mode 2 +58 1 External Port Mode 3 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +152 2 External Port Data 1 +154 2 External Port Data 2 +156 2 External Port Data 3 +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xw430_t200.model b/control_table/xw430_t200.model new file mode 100644 index 000000000..f9c057569 --- /dev/null +++ b/control_table/xw430_t200.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xw430_t333.model b/control_table/xw430_t333.model new file mode 100644 index 000000000..f9c057569 --- /dev/null +++ b/control_table/xw430_t333.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xw540_h260.model b/control_table/xw540_h260.model new file mode 100644 index 000000000..f9c057569 --- /dev/null +++ b/control_table/xw540_h260.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xw540_t140.model b/control_table/xw540_t140.model new file mode 100644 index 000000000..f9c057569 --- /dev/null +++ b/control_table/xw540_t140.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/xw540_t260.model b/control_table/xw540_t260.model new file mode 100644 index 000000000..f9c057569 --- /dev/null +++ b/control_table/xw540_t260.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 1 Baud Rate +9 1 Return Delay Time +10 1 Drive Mode +11 1 Operating Mode +12 1 Secondary(Shadow) ID +13 1 Protocol Type +20 4 Homing Offset +24 4 Moving Threshold +31 1 Temperature Limit +32 2 Max Voltage Limit +34 2 Min Voltage Limit +36 2 PWM Limit +38 2 Current Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 Bus Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/control_table/ym070_210_a051.model b/control_table/ym070_210_a051.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_a051.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym070_210_a099.model b/control_table/ym070_210_a099.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_a099.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym070_210_b001.model b/control_table/ym070_210_b001.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_b001.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym070_210_m001.model b/control_table/ym070_210_m001.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_m001.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym070_210_r051.model b/control_table/ym070_210_r051.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_r051.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym070_210_r099.model b/control_table/ym070_210_r099.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym070_210_r099.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_a051.model b/control_table/ym080_230_a051.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_a051.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_a099.model b/control_table/ym080_230_a099.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_a099.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_b001.model b/control_table/ym080_230_b001.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_b001.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_m001.model b/control_table/ym080_230_m001.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_m001.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_r051.model b/control_table/ym080_230_r051.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_r051.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/control_table/ym080_230_r099.model b/control_table/ym080_230_r099.model new file mode 100644 index 000000000..72a20d37a --- /dev/null +++ b/control_table/ym080_230_r099.model @@ -0,0 +1,115 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0010471976 rad/s signed +Goal Velocity 0.0010471976 rad/s signed +Present Current 1.0 raw signed +Goal Current 1.0 raw signed + +[control table] +Address Size Data Name +0 2 Model Number +2 4 Model Information +6 1 Firmware Version +7 1 ID +8 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/python/setup.py b/python/setup.py index cd00d63e8..d0ea4045c 100644 --- a/python/setup.py +++ b/python/setup.py @@ -13,7 +13,7 @@ setup( name='dynamixel_sdk', - version='3.8.4', + version='4.0.0', packages=['dynamixel_sdk'], package_dir={'': 'src'}, license='Apache 2.0', diff --git a/ros/dynamixel_sdk/CHANGELOG.rst b/ros/dynamixel_sdk/CHANGELOG.rst index a2535fc83..c0f8666e9 100644 --- a/ros/dynamixel_sdk/CHANGELOG.rst +++ b/ros/dynamixel_sdk/CHANGELOG.rst @@ -2,6 +2,10 @@ Changelog for package dynamixel_sdk ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.0.0 (2025-10-14) +------------------ +* None + 3.8.4 (2025-05-28) ------------------ * Deprecate ament_include_dependency usage in CMakeLists.txt diff --git a/ros/dynamixel_sdk/package.xml b/ros/dynamixel_sdk/package.xml index 4a23c05f2..49bd86cca 100644 --- a/ros/dynamixel_sdk/package.xml +++ b/ros/dynamixel_sdk/package.xml @@ -2,7 +2,7 @@ dynamixel_sdk - 3.8.4 + 4.0.0 This package is wrapping version of ROBOTIS Dynamixel SDK for ROS 2. The ROBOTIS Dynamixel SDK, or SDK, is a software development library that provides Dynamixel control functions for packet communication. The API is designed for Dynamixel actuators and Dynamixel-based platforms. diff --git a/ros/dynamixel_sdk_custom_interfaces/CHANGELOG.rst b/ros/dynamixel_sdk_custom_interfaces/CHANGELOG.rst index ef6c64237..860d100e3 100644 --- a/ros/dynamixel_sdk_custom_interfaces/CHANGELOG.rst +++ b/ros/dynamixel_sdk_custom_interfaces/CHANGELOG.rst @@ -2,6 +2,10 @@ Changelog for package dynamixel_sdk_custom_interfaces ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.0.0 (2025-10-14) +------------------ +* None + 3.8.4 (2025-05-28) ------------------ * None diff --git a/ros/dynamixel_sdk_custom_interfaces/package.xml b/ros/dynamixel_sdk_custom_interfaces/package.xml index 0a0eab411..365f7332d 100644 --- a/ros/dynamixel_sdk_custom_interfaces/package.xml +++ b/ros/dynamixel_sdk_custom_interfaces/package.xml @@ -2,7 +2,7 @@ dynamixel_sdk_custom_interfaces - 3.8.4 + 4.0.0 ROS 2 custom interface examples using ROBOTIS DYNAMIXEL SDK Pyo Apache 2.0 diff --git a/ros/dynamixel_sdk_examples/CHANGELOG.rst b/ros/dynamixel_sdk_examples/CHANGELOG.rst index cc063aa6d..667f676c8 100644 --- a/ros/dynamixel_sdk_examples/CHANGELOG.rst +++ b/ros/dynamixel_sdk_examples/CHANGELOG.rst @@ -2,6 +2,10 @@ Changelog for package dynamixel_sdk_examples ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +4.0.0 (2025-10-14) +------------------ +* None + 3.8.4 (2025-05-28) ------------------ * Deprecate ament_include_dependency usage in CMakeLists.txt diff --git a/ros/dynamixel_sdk_examples/package.xml b/ros/dynamixel_sdk_examples/package.xml index 7a7e3dc3a..630a2ce9f 100644 --- a/ros/dynamixel_sdk_examples/package.xml +++ b/ros/dynamixel_sdk_examples/package.xml @@ -1,7 +1,7 @@ dynamixel_sdk_examples - 3.8.4 + 4.0.0 ROS 2 examples using ROBOTIS DYNAMIXEL SDK Apache 2.0 Pyo