Skip to content

Commit 3f01851

Browse files
committed
high torque threshold
1 parent b176fe2 commit 3f01851

File tree

3 files changed

+26
-17
lines changed

3 files changed

+26
-17
lines changed

mep3_hardware/include/mep3_hardware/dynamixel_hardware_interface/dynamixel_hardware.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,16 +44,16 @@ struct JointState
4444
double voltage{0.0};
4545
double temperature{0.0};
4646
bool overloaded;
47+
double recovery_position_{0.0};
4748
std::deque<double> previous_efforts_{};
48-
std::optional<std::chrono::time_point<std::chrono::system_clock>> last_max_effort_{};
49+
std::optional<std::chrono::time_point<std::chrono::system_clock>> high_torque_start{};
4950
};
5051

5152
struct JointCommand
5253
{
5354
double position{0.0};
5455
double velocity{0.0};
5556
double effort{0.0};
56-
double initial_position_{0.0};
5757
};
5858

5959
struct Joint
@@ -123,6 +123,7 @@ class DynamixelHardware
123123
double offset_{0};
124124
bool keep_read_write_thread_{true};
125125
unsigned int effort_average_ {0};
126+
double torque_threshold_ {0.9};
126127
std::chrono::milliseconds recovery_timeout_{250};
127128
};
128129
} // namespace dynamixel_hardware

mep3_hardware/src/dynamixel_hardware_interface/dynamixel_hardware.cpp

Lines changed: 22 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ namespace dynamixel_hardware
5050

5151
CallbackReturn DynamixelHardware::on_init(const hardware_interface::HardwareInfo &info)
5252
{
53-
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "configure");
53+
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "Configure");
5454
if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
5555
{
5656
return CallbackReturn::ERROR;
@@ -80,11 +80,11 @@ namespace dynamixel_hardware
8080
joints_[i].state.voltage = std::numeric_limits<double>::quiet_NaN();
8181
joints_[i].state.temperature = std::numeric_limits<double>::quiet_NaN();
8282
// Bookkeeping
83-
joints_[i].command.initial_position_ = std::numeric_limits<double>::quiet_NaN();
83+
joints_[i].state.recovery_position_ = std::numeric_limits<double>::quiet_NaN();
8484
joints_[i].state.overloaded = false;
8585
joints_[i].state.previous_efforts_ = std::deque<double>();
8686
joints_[i].state.previous_efforts_.resize(effort_average_);
87-
joints_[i].state.last_max_effort_.reset();
87+
joints_[i].state.high_torque_start.reset();
8888
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "joint_id %d: %d", i, joint_ids_[i]);
8989
}
9090

@@ -113,6 +113,13 @@ namespace dynamixel_hardware
113113
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "recovery_timeout: %ld ms [default]", recovery_timeout_.count());
114114
}
115115

116+
try {
117+
torque_threshold_ = stof(info_.hardware_parameters.at("torque_threshold"));
118+
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "torque_threshold: %.2f", torque_threshold_);
119+
} catch (const std::out_of_range& e) {
120+
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "torque_threshold: %.2f [default]", torque_threshold_);
121+
}
122+
116123
if (!dynamixel_workbench_.init(usb_port.c_str(), baud_rate, &log))
117124
{
118125
RCLCPP_FATAL(rclcpp::get_logger(kDynamixelHardware), "%s", log);
@@ -271,7 +278,7 @@ namespace dynamixel_hardware
271278

272279
CallbackReturn DynamixelHardware::on_activate(const rclcpp_lifecycle::State & /* previous_state */)
273280
{
274-
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "start");
281+
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "Start");
275282
for (uint i = 0; i < joints_.size(); i++)
276283
{
277284
if (use_dummy_ && std::isnan(joints_[i].state.position))
@@ -286,7 +293,7 @@ namespace dynamixel_hardware
286293
for (uint i = 0; i < joints_.size(); i++)
287294
{
288295
// Save initial position for recovery
289-
joints_[i].command.initial_position_ = joints_[i].state.position;
296+
joints_[i].state.recovery_position_ = joints_[i].state.position;
290297
}
291298
reset_command();
292299
write_to_hardware();
@@ -311,7 +318,7 @@ namespace dynamixel_hardware
311318
CallbackReturn DynamixelHardware::on_deactivate(const rclcpp_lifecycle::State & /* previous_state */)
312319
{
313320
keep_read_write_thread_ = false;
314-
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "stop");
321+
RCLCPP_DEBUG(rclcpp::get_logger(kDynamixelHardware), "Stop");
315322
return CallbackReturn::SUCCESS;
316323
}
317324

@@ -467,7 +474,7 @@ namespace dynamixel_hardware
467474

468475
int16_t load = (present_data[4] | ((0x3 & present_data[5]) << 8));
469476
bool overload = (unsigned) load > TORQUE_LOAD_MAX;
470-
bool max_torque = (unsigned) load == TORQUE_LOAD_MAX;
477+
bool high_torque = (double) load >= TORQUE_LOAD_MAX * torque_threshold_;
471478
// data[5] third bit determines effort sign
472479
if (present_data[5] & 0x4)
473480
load = -load;
@@ -496,25 +503,25 @@ namespace dynamixel_hardware
496503
joints_[i].state.effort = std::numeric_limits<double>::infinity();
497504
}
498505

499-
if (max_torque) {
500-
if (joints_[i].state.last_max_effort_.has_value()) {
501-
const auto time_delta = std::chrono::system_clock::now() - joints_[i].state.last_max_effort_.value();
506+
if (high_torque) {
507+
if (joints_[i].state.high_torque_start.has_value()) {
508+
const auto time_delta = std::chrono::system_clock::now() - joints_[i].state.high_torque_start.value();
502509
const auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(time_delta);
503510
if (duration > recovery_timeout_) {
504511
RCLCPP_WARN(
505512
rclcpp::get_logger(kDynamixelHardware),
506-
"Recovering stuck joint %s to initial position %.3lf",
513+
"Recovering stuck joint %s to position %.3lf",
507514
info_.joints[i].name.c_str(),
508-
joints_[i].command.initial_position_
515+
joints_[i].state.recovery_position_
509516
);
510-
joints_[i].command.position = joints_[i].command.initial_position_;
517+
joints_[i].command.position = joints_[i].state.recovery_position_;
511518
joints_[i].state.effort = std::numeric_limits<double>::infinity();
512519
}
513520
} else {
514-
joints_[i].state.last_max_effort_ = std::chrono::system_clock::now();
521+
joints_[i].state.high_torque_start = std::chrono::system_clock::now();
515522
}
516523
} else {
517-
joints_[i].state.last_max_effort_.reset();
524+
joints_[i].state.high_torque_start.reset();
518525
}
519526

520527
// RCLCPP_WARN(

mep3_hardware/test/dynamixel/description.urdf

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
<param name="use_dummy">false</param>
1010
<param name="offset">0.0</param>
1111
<param name="effort_average">2</param>
12+
<param name="torque_threshold">0.8</param>
1213
<param name="recovery_timeout">100</param>
1314
</hardware>
1415
<joint name="joint1">

0 commit comments

Comments
 (0)