@@ -35,7 +35,11 @@ DynamixelHardware::DynamixelHardware()
35
35
{
36
36
dxl_status_ = DXL_OK;
37
37
dxl_torque_status_ = TORQUE_ENABLED;
38
- err_timeout_sec_ = 3.0 ;
38
+ err_timeout_ms_ = 500 ;
39
+ is_read_in_error_ = false ;
40
+ is_write_in_error_ = false ;
41
+ read_error_duration_ = rclcpp::Duration (0 , 0 );
42
+ write_error_duration_ = rclcpp::Duration (0 , 0 );
39
43
}
40
44
41
45
DynamixelHardware::~DynamixelHardware ()
@@ -64,7 +68,11 @@ hardware_interface::CallbackReturn DynamixelHardware::on_init(
64
68
65
69
port_name_ = info_.hardware_parameters [" port_name" ];
66
70
baud_rate_ = info_.hardware_parameters [" baud_rate" ];
67
- err_timeout_sec_ = stod (info_.hardware_parameters [" error_timeout_sec" ]);
71
+ try {
72
+ err_timeout_ms_ = stod (info_.hardware_parameters [" error_timeout_ms" ]);
73
+ } catch (const std::exception& e) {
74
+ RCLCPP_ERROR (logger_, " Failed to parse error_timeout_ms parameter: %s, using default value" , e.what ());
75
+ }
68
76
69
77
RCLCPP_INFO_STREAM (
70
78
logger_,
@@ -394,11 +402,23 @@ hardware_interface::return_type DynamixelHardware::read(
394
402
} else if (dxl_status_ == DXL_OK || dxl_status_ == COMM_ERROR) {
395
403
dxl_comm_err_ = CheckError (dxl_comm_->ReadMultiDxlData ());
396
404
if (dxl_comm_err_ != DxlError::OK) {
405
+ if (!is_read_in_error_) {
406
+ is_read_in_error_ = true ;
407
+ read_error_duration_ = rclcpp::Duration (0 , 0 );
408
+ }
409
+ read_error_duration_ = read_error_duration_ + period;
410
+
397
411
RCLCPP_ERROR_STREAM (
398
412
logger_,
399
- " Dynamixel Read Fail :" << Dynamixel::DxlErrorToString (dxl_comm_err_));
400
- return hardware_interface::return_type::ERROR;
413
+ " Dynamixel Read Fail (Duration: " << read_error_duration_.seconds () * 1000 << " ms/" << err_timeout_ms_ << " ms)" );
414
+
415
+ if (read_error_duration_.seconds () * 1000 >= err_timeout_ms_) {
416
+ return hardware_interface::return_type::ERROR;
417
+ }
418
+ return hardware_interface::return_type::OK;
401
419
}
420
+ is_read_in_error_ = false ;
421
+ read_error_duration_ = rclcpp::Duration (0 , 0 );
402
422
} else if (dxl_status_ == HW_ERROR) {
403
423
dxl_comm_err_ = CheckError (dxl_comm_->ReadMultiDxlData ());
404
424
if (dxl_comm_err_ != DxlError::OK) {
@@ -434,7 +454,6 @@ hardware_interface::return_type DynamixelHardware::read(
434
454
}
435
455
return hardware_interface::return_type::OK;
436
456
}
437
-
438
457
hardware_interface::return_type DynamixelHardware::write (
439
458
const rclcpp::Time & time, const rclcpp::Duration & period)
440
459
{
@@ -447,16 +466,28 @@ hardware_interface::return_type DynamixelHardware::write(
447
466
448
467
dxl_comm_->WriteMultiDxlData ();
449
468
469
+ is_write_in_error_ = false ;
470
+ write_error_duration_ = rclcpp::Duration (0 , 0 );
471
+
450
472
return hardware_interface::return_type::OK;
451
473
} else {
452
- RCLCPP_ERROR_STREAM (logger_, " Dynamixel Write Fail" );
453
- return hardware_interface::return_type::ERROR;
474
+ write_error_duration_ = write_error_duration_ + period;
475
+
476
+ RCLCPP_ERROR_STREAM (
477
+ logger_,
478
+ " Dynamixel Write Fail (Duration: " << write_error_duration_.seconds () * 1000 << " ms/" << err_timeout_ms_ << " ms)" );
479
+
480
+ if (write_error_duration_.seconds () * 1000 >= err_timeout_ms_) {
481
+ return hardware_interface::return_type::ERROR;
482
+ }
483
+ return hardware_interface::return_type::OK;
454
484
}
455
485
}
456
486
457
487
DxlError DynamixelHardware::CheckError (DxlError dxl_comm_err)
458
488
{
459
489
DxlError error_state = DxlError::OK;
490
+ dxl_status_ = DXL_OK;
460
491
461
492
// check comm error
462
493
if (dxl_comm_err != DxlError::OK) {
0 commit comments