ROBOTIS-GIT / DynamixelSDK

ROBOTIS Dynamixel SDK (Protocol1.0/2.0)
http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/
Apache License 2.0
454 stars 405 forks source link

[read_write_node]: [TxRxResult] There is no status packet! #556

Open Alberto-D opened 2 years ago

Alberto-D commented 2 years ago
  1. Which DYNAMIXEL SDK version do you use? 3.7.42, just downloaded it from github

  2. Which programming language/tool do you use? C++ and ROS 2 foxy , just followed this video https://www.youtube.com/watch?v=E8XPqDjof4U&lc=UgzLGFvmiJ2jGCAhF7h4AaABAg.9_CTmLi7sjU9_EBWtxBD9V

  3. Which operating system do you use? Ubuntu 20.04

  4. Which USB serial converter do you use? U2D2 from the Dynamixel starter set

  5. Which DYNAMIXEL do you use? AX-18A

  6. Have you searched the issue from the closed issue threads? Yes, there are similar results like https://github.com/ROBOTIS-GIT/DynamixelSDK/issues/535 , but their solutions did not work,

  7. Please describe the issue in detail

When I try to move the motor using $ ros2 topic pub -1 /set_position dynamixel_sdk_custom_interfaces/msg/SetPosition "{id: 1, position: 2000}" , the terminal where I launched $ ros2 run dynamixel_sdk_examples read_write_node gives the next: [INFO] [1648743728.153716516] [read_write_node]: Succeeded to open the port. [INFO] [1648743728.154536648] [read_write_node]: Succeeded to set the baudrate. [INFO] [1648743728.154596555] [read_write_node]: Succeeded to set Position Control Mode. [INFO] [1648743728.154631328] [read_write_node]: Succeeded to enable torque. [INFO] [1648743728.179269757] [read_write_node]: Run read write node [INFO] [1648743820.779849420] [read_write_node]: [TxRxResult] There is no status packet!

I tried changing the baudrate to the required for this model (7343bps ~ 1 Mbps) and got the same error, except if i use 1000000 baudrate i get [read_write_node]: [RxPacketError] Overheat error!, I tried the parameters from the linked issue in section 5 of the post ( baudrate, ADDR_TORQUE_ENABLE, ADDR_GOAL_POSITION and ADDR_PRESENT_POSITION) but got the same result.

The other motor I have is the XL-320, which is the only exception for the X series as said in the github example( https://github.com/ROBOTIS-GIT/DynamixelSDK/blob/foxy-devel/dynamixel_sdk_examples/src/read_write_node.cpp ), so if someone knows the Control table address for this model i wloud apreciate it, i tried using the data from https://emanual.robotis.com/docs/en/dxl/x/xl320/

define ADDR_OPERATING_MODE 2

define ADDR_TORQUE_ENABLE 24

define ADDR_GOAL_POSITION 30

define ADDR_PRESENT_POSITION 37

but didn't work either.

  1. How can we reproduce the issue? Using the same hardware should give the same result.
ROBOTIS-Will commented 2 years ago

Hi @Alberto-D Make sure you have an access to the USB port. Below command will add your account to the dialout group to read / write the USB port

$ sudo usermod -aG dialout {your_linux_account}

Thanks!

Alberto-D commented 2 years ago

Already did it, but i get the same error

Alberto-D commented 2 years ago

Also tried a brand new installation in a raspberry pi 4 4gb and get the same error

ROBOTIS-Will commented 2 years ago

Hi @Alberto-D I'm sorry about the delayed response.

Could you share the entire code you have tested so that I can try it as well? Also, please let me know if you have any non-default configuration in your AX-12.

Thanks!

Alberto-D commented 2 years ago

Here is all the code, i don think i have any non default configuration, i just got them out of the box and tried the tutorial, but the motors are AX-18A no AX-12

// Copyright 2021 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.

/ // This example is written for DYNAMIXEL X(excluding XL-320) and MX(2.0) series with U2D2. // For other series, please refer to the product eManual and modify the Control Table addresses and other definitions. // To test this example, please follow the commands below. // // Open terminal #1 // $ ros2 run dynamixel_sdk_examples read_write_node // // Open terminal #2 (run one of below commands at a time) // $ ros2 topic pub -1 /set_position dynamixel_sdk_custom_interfaces/SetPosition "{id: 1, position: 1000}" // $ ros2 service call /get_position dynamixel_sdk_custom_interfaces/srv/GetPosition "id: 1" // // Author: Will Son /

include

include

include

include "dynamixel_sdk/dynamixel_sdk.h"

include "dynamixel_sdk_custom_interfaces/msg/set_position.hpp"

include "dynamixel_sdk_custom_interfaces/srv/get_position.hpp"

include "rclcpp/rclcpp.hpp"

include "rcutils/cmdline_parser.h"

include "read_write_node.hpp"

// Control table address for X series (except XL-320)

define ADDR_OPERATING_MODE 1

define ADDR_TORQUE_ENABLE 24

define ADDR_GOAL_POSITION 30

define ADDR_PRESENT_POSITION 37

// Protocol version

define PROTOCOL_VERSION 1.0 //Protocol for DYNAMIXEL AX

// Default setting

define BAUDRATE 1000000 // Default Baudrate of DYNAMIXEL AX series

define DEVICE_NAME "/dev/ttyUSB0" // [Linux]: "/dev/ttyUSB", [Windows]: "COM"

dynamixel::PortHandler portHandler; dynamixel::PacketHandler packetHandler;

uint8_t dxl_error = 0; uint32_t goal_position = 0; int dxl_comm_result = COMM_TX_FAIL;

ReadWriteNode::ReadWriteNode() : Node("read_write_node") { RCLCPP_INFO(this->get_logger(), "Run read write node");

this->declare_parameter("qos_depth", 10); int8_t qos_depth = 0; this->get_parameter("qos_depth", qos_depth);

const auto QOS_RKL10V = rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

set_positionsubscriber = this->create_subscription( "set_position", QOS_RKL10V, [this](const SetPosition::SharedPtr msg) -> void { uint8_t dxl_error = 0;

  // Position Value of X series is 4 byte data.
  // For AX & MX(1.0) use 2 byte data(uint16_t) for the Position Value.
  uint32_t goal_position = (unsigned int)msg->position;  // Convert int32 -> uint32

  // Write Goal Position (length : 4 bytes)
  // When writing 2 byte data to AX / MX(1.0), use write2ByteTxRx() instead.
  dxl_comm_result =
  packetHandler->write4ByteTxRx(
    portHandler,
    (uint8_t) msg->id,
    ADDR_GOAL_POSITION,
    goal_position,
    &dxl_error
  );

  if (dxl_comm_result != COMM_SUCCESS) {
    RCLCPP_INFO(this->get_logger(), "%s", packetHandler->getTxRxResult(dxl_comm_result));
  } else if (dxl_error != 0) {
    RCLCPP_INFO(this->get_logger(), "%s", packetHandler->getRxPacketError(dxl_error));
  } else {
    RCLCPP_INFO(this->get_logger(), "Set [ID: %d] [Goal Position: %d]", msg->id, msg->position);
  }
}
);

auto get_present_position = [this]( const std::shared_ptr request, std::shared_ptr response) -> void { // Read Present Position (length : 4 bytes) and Convert uint32 -> int32 // When reading 2 byte data from AX / MX(1.0), use read2ByteTxRx() instead. dxl_comm_result = packetHandler->read4ByteTxRx( portHandler, (uint8_t) request->id, ADDR_PRESENT_POSITION, reinterpret_cast<uint32_t *>(&present_position), &dxl_error );

  RCLCPP_INFO(
    this->get_logger(),
    "Get [ID: %d] [Present Position: %d]",
    request->id,
    present_position
  );

  response->position = present_position;
};

get_positionserver = create_service("get_position", get_present_position); }

ReadWriteNode::~ReadWriteNode() { }

void setupDynamixel(uint8_t dxl_id) { // Use Position Control Mode dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_OPERATING_MODE, 3, &dxl_error );

if (dxl_comm_result != COMM_SUCCESS) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to set Position Control Mode."); } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to set Position Control Mode."); }

// Enable Torque of DYNAMIXEL dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_TORQUE_ENABLE, 1, &dxl_error );

if (dxl_comm_result != COMM_SUCCESS) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to enable torque."); } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to enable torque."); } }

int main(int argc, char * argv[]) { portHandler = dynamixel::PortHandler::getPortHandler(DEVICE_NAME); packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION);

// Open Serial Port dxl_comm_result = portHandler->openPort(); if (dxl_comm_result == false) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to open the port!"); return -1; } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to open the port."); }

// Set the baudrate of the serial port (use DYNAMIXEL Baudrate) dxl_comm_result = portHandler->setBaudRate(BAUDRATE); if (dxl_comm_result == false) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to set the baudrate!"); return -1; } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to set the baudrate."); }

setupDynamixel(BROADCAST_ID);

rclcpp::init(argc, argv);

auto readwritenode = std::make_shared(); rclcpp::spin(readwritenode); rclcpp::shutdown();

// Disable Torque of DYNAMIXEL packetHandler->write1ByteTxRx( portHandler, BROADCAST_ID, ADDR_TORQUE_ENABLE, 0, &dxl_error );

return 0; }

Alberto-D commented 2 years ago

It worked, thanks. One last question, Is there a way to control the motors using speed instead of position with ROS?

ROBOTIS-Will commented 2 years ago

Hi @Alberto-D

You may change the target address from Goal Position to Moving Speed as they have the same size data field. You'll also need to change to Operation Type before running the code.

Thanks!

sanjiblama28 commented 1 year ago

Here is all the code, i don think i have any non default configuration, i just got them out of the box and tried the tutorial, but the motors are AX-18A no AX-12

// Copyright 2021 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.

/ // This example is written for DYNAMIXEL X(excluding XL-320) and MX(2.0) series with U2D2. // For other series, please refer to the product eManual and modify the Control Table addresses and other definitions. // To test this example, please follow the commands below. // // Open terminal #1 // $ ros2 run dynamixel_sdk_examples read_write_node // // Open terminal #2 (run one of below commands at a time) // $ ros2 topic pub -1 /set_position dynamixel_sdk_custom_interfaces/SetPosition "{id: 1, position: 1000}" // $ ros2 service call /get_position dynamixel_sdk_custom_interfaces/srv/GetPosition "id: 1" // // Author: Will Son /

include #include #include

include "dynamixel_sdk/dynamixel_sdk.h" #include "dynamixel_sdk_custom_interfaces/msg/set_position.hpp" #include "dynamixel_sdk_custom_interfaces/srv/get_position.hpp" #include "rclcpp/rclcpp.hpp" #include "rcutils/cmdline_parser.h"

include "read_write_node.hpp"

// Control table address for X series (except XL-320) #define ADDR_OPERATING_MODE 1 #define ADDR_TORQUE_ENABLE 24 #define ADDR_GOAL_POSITION 30 #define ADDR_PRESENT_POSITION 37

// Protocol version #define PROTOCOL_VERSION 1.0 //Protocol for DYNAMIXEL AX

// Default setting #define BAUDRATE 1000000 // Default Baudrate of DYNAMIXEL AX series #define DEVICE_NAME "/dev/ttyUSB0" // [Linux]: "/dev/ttyUSB", [Windows]: "COM"

dynamixel::PortHandler portHandler; dynamixel::PacketHandler packetHandler;

uint8_t dxl_error = 0; uint32_t goal_position = 0; int dxl_comm_result = COMM_TX_FAIL;

ReadWriteNode::ReadWriteNode() : Node("read_write_node") { RCLCPP_INFO(this->get_logger(), "Run read write node");

this->declare_parameter("qos_depth", 10); int8_t qos_depth = 0; this->get_parameter("qos_depth", qos_depth);

const auto QOS_RKL10V = rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

set_positionsubscriber = this->create_subscription( "set_position", QOS_RKL10V, [this](const SetPosition::SharedPtr msg) -> void { uint8_t dxl_error = 0;

  // Position Value of X series is 4 byte data.
  // For AX & MX(1.0) use 2 byte data(uint16_t) for the Position Value.
  uint32_t goal_position = (unsigned int)msg->position;  // Convert int32 -> uint32

  // Write Goal Position (length : 4 bytes)
  // When writing 2 byte data to AX / MX(1.0), use write2ByteTxRx() instead.
  dxl_comm_result =
  packetHandler->write4ByteTxRx(
    portHandler,
    (uint8_t) msg->id,
    ADDR_GOAL_POSITION,
    goal_position,
    &dxl_error
  );

  if (dxl_comm_result != COMM_SUCCESS) {
    RCLCPP_INFO(this->get_logger(), "%s", packetHandler->getTxRxResult(dxl_comm_result));
  } else if (dxl_error != 0) {
    RCLCPP_INFO(this->get_logger(), "%s", packetHandler->getRxPacketError(dxl_error));
  } else {
    RCLCPP_INFO(this->get_logger(), "Set [ID: %d] [Goal Position: %d]", msg->id, msg->position);
  }
}
);

auto get_present_position = [this]( const std::shared_ptrGetPosition::Request request, std::shared_ptrGetPosition::Response response) -> void { // Read Present Position (length : 4 bytes) and Convert uint32 -> int32 // When reading 2 byte data from AX / MX(1.0), use read2ByteTxRx() instead. dxl_comm_result = packetHandler->read4ByteTxRx( portHandler, (uint8_t) request->id, ADDR_PRESENT_POSITION, reinterpret_cast<uint32_t *>(&present_position), &dxl_error );

  RCLCPP_INFO(
    this->get_logger(),
    "Get [ID: %d] [Present Position: %d]",
    request->id,
    present_position
  );

  response->position = present_position;
};

get_positionserver = create_service("get_position", get_present_position); }

ReadWriteNode::~ReadWriteNode() { }

void setupDynamixel(uint8_t dxl_id) { // Use Position Control Mode dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_OPERATING_MODE, 3, &dxl_error );

if (dxl_comm_result != COMM_SUCCESS) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to set Position Control Mode."); } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to set Position Control Mode."); }

// Enable Torque of DYNAMIXEL dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_TORQUE_ENABLE, 1, &dxl_error );

if (dxl_comm_result != COMM_SUCCESS) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to enable torque."); } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to enable torque."); } }

int main(int argc, char * argv[]) { portHandler = dynamixel::PortHandler::getPortHandler(DEVICE_NAME); packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION);

// Open Serial Port dxl_comm_result = portHandler->openPort(); if (dxl_comm_result == false) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to open the port!"); return -1; } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to open the port."); }

// Set the baudrate of the serial port (use DYNAMIXEL Baudrate) dxl_comm_result = portHandler->setBaudRate(BAUDRATE); if (dxl_comm_result == false) { RCLCPP_ERROR(rclcpp::get_logger("read_write_node"), "Failed to set the baudrate!"); return -1; } else { RCLCPP_INFO(rclcpp::get_logger("read_write_node"), "Succeeded to set the baudrate."); }

setupDynamixel(BROADCAST_ID);

rclcpp::init(argc, argv);

auto readwritenode = std::make_shared(); rclcpp::spin(readwritenode); rclcpp::shutdown();

// Disable Torque of DYNAMIXEL packetHandler->write1ByteTxRx( portHandler, BROADCAST_ID, ADDR_TORQUE_ENABLE, 0, &dxl_error );

return 0; }

Hello @Alberto-D Could I know how you resolve this problem? I am stuck in this problem.

MOLOCH-dev commented 1 year ago

Hello, Did you check the id of your dynamixel using the dynamixel wizard? If it is indeed 1 then the code should work, otherwise your id might be different.