Open wyd0817 opened 3 years ago
Hi @wyd0817 Have you tried the sync_read_write example in the SDK? Since the dxl_present_position is an int32_t, it could become 0 if it is smaller than 1.0 when printing with %d option as you are dividing it to 4096, but never convert it to double or float.
Hi, thanks for your reply. I found my problem. There is a logic error in the program. I'll post the correct code below. cheers
int32_t DynamixelControl::DynamixelReadPresentPosition(int id)
{
// Initialize Groupsyncread instance for Present Position
dynamixel::GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_XH_PRESENT_POSITION, LEN_XH_PRESENT_POSITION);
int dxl_comm_result = COMM_TX_FAIL; // Communication result
bool dxl_addparam_result = false; // addParam result
bool dxl_getdata_result = false; // GetParam result
int32_t dxl_present_position = 0;
for(uint8_t ID=0; ID<id; ID++){
// Add parameter storage for Dynamixel#1 present position value
dxl_addparam_result = groupSyncRead.addParam((uint8_t)ID);
if (dxl_addparam_result != true)
{
ROS_ERROR("Failed to addparam to groupSyncRead for Dynamixel ID %d", ID);
return 0;
}
}
// Syncread present position
dxl_comm_result = groupSyncRead.txRxPacket();
if (dxl_comm_result == COMM_SUCCESS){
for(uint8_t ID=0; ID<id; ID++){
// Get Dynamixel#1 present position value
dxl_present_position = groupSyncRead.getData((uint8_t)ID, ADDR_XH_PRESENT_POSITION, LEN_XH_PRESENT_POSITION);
// ROS_INFO("getPosition : POSITION[%02d]:%03d[deg]", ID, dxl_present_position*360/4096);
joint_data4V2.joint_index = ID;
joint_data4V2.position.push_back((dxl_present_position*360/4096)-180); // [deg]
joint_data_for_copsim.data.push_back((dxl_present_position*360/4096)-180);// [deg]
}
groupSyncRead.clearParam();
return true;
} else {
ROS_ERROR("Failed to get position! Result: %d", dxl_comm_result);
groupSyncRead.clearParam();
return false;
}
}
I have two more questions. I don't know if I should ask under this issue or not. But I would like to know why I often get time out errors when I connect 25 xh430-w350 in series, even if I use DYNAMIXEL Wizard 2.0, although it''s ignorable to the extent that it''s ignorable? Is there any information about the friction (moment of inertia and damping, etc.) of the xh430-w350, which may be used in some of my research?
Hi @wyd0817 What do you set Baudrate for XM430? If it is 57600bps that in the factory set, communication with 25 XM430s may not be successful. For reference, our OpenMANIPULATOR-X has 5 XM430, the Baudrate is 1Mbps. Our Humanoid roobt ROBOTIS OP3 that using 20 XM430 is 3Mbps.
Hi, I have 25 motors with a baud rate of 3Mbps and my motor is xh430-w350.
Hi, I C. There is no difference in communication circuit and FW function between XM430 and XH430. Excuse me.
Hi. Thank you, do you know the answers to my other two questions? Does it have to do with setting the return time? My previous Return Delay Times were all defaulted to 250 and the computer and the 25 motors could not communicate at all. When I set it to 0, the computer can communicate with the 25 motors, but something will have some time out errors.
Hi, If you change the value to 1 instead of 0, any improvement? Image is the setting of OP3 that have 20 pcs of X430. It sets the delay time to 1. I apologize for the wrong OP3 Baud rate in a previous post, correct is at 2Mbps.
@wyd0817
If you have connected all 25 DYNAMIXEL modules in a single chain, you may get some issue due to the resistance caused by each connector and cable. When the resistance builds up, the ground voltage as a reference may distorted and affect the communication. In order to resolve this issue, I'd recommend jump the power(VDD, GND) every 10~15 DYNAMIXEL.
For more accurate diagnosis, please let us how 25 DYNAMIXEL are connected to the controller and the power source. Thanks.
@ROBOTIS-Shibata Hi, I'm sorry for the late reply. I changed the value of Return Deley Time from 0 to 1 and it still has the same error. My baud rate is set to 3Mbps. Time out error even with DYNAMIXEL Wizard 2.0.
@ROBOTIS-Will Hi, this is how my robot is connected.
Hi @wyd0817 If you have daisy chained all 25 modules, make sure to jump the power to every 4~5 DYNAMIXEL so that their ground can be stablized and the sufficient power can be delivered to all connected DYNAMIXEL. Also appending 120 ohm termination resistor at the end of the chain could resolve communication problem. Thank you.
Hi, Thank you for your reply. I've been busy with my thesis for a while, sorry for the late reply. Yes, I have daisy chained all 25 modules. Due to the structure of my robot, I can't make sure to jump the power supply every 4-5 DYNAMIXEL for now, but I will consider it. I added 120 ohm termination resistors at the end of the chain D+ and D- it seems that the number of errors is not reduced, even if it still communicates like the original. Thanks!
Hi @wyd0817 Sorry about the delayed response. When connecting several DYNAMIXEL in series, power jump is very important as there are some resistance build up on the cable and connectors which distorts the voltage of the communication signal. Thanks.
Hello, With Sync Read instructions you can send multiple motor angles, but you can't read the angle of multiple motors, you can only read the angle of the first motor, the other angle values are zero. Thank you for any help or possible solution you can offer me. Platform: ros melodic DYNAMIXEL SDK version : melodic-devel Communication protocol: 2.0 Dynamixel firmware version: 44 Hardware: Ubuntu 18.04.5 LTS+USB2Dynamixel+six xh430 w250 motors
Here is my synchronous read angle function.