Skip to content

Commit 9835526

Browse files
committed
fix: Static variable problem when using multiple DynamixelHardwareInterface in one ros2_control_node
1 parent e354023 commit 9835526

File tree

2 files changed

+8
-6
lines changed

2 files changed

+8
-6
lines changed

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -245,6 +245,8 @@ class DynamixelHardware : public
245245
std::vector<HandlerVarType> hdl_gpio_sensor_states_;
246246
std::vector<HandlerVarType> hdl_sensor_states_;
247247

248+
bool is_set_hdl_{false};
249+
248250
// joint <-> transmission matrix
249251
size_t num_of_joints_;
250252
size_t num_of_transmissions_;

src/dynamixel_hardware_interface.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -627,9 +627,9 @@ bool DynamixelHardware::InitDxlItems()
627627
bool DynamixelHardware::InitDxlReadItems()
628628
{
629629
RCLCPP_INFO_STREAM(logger_, "$$$$$ Init Dxl Read Items");
630-
static bool is_set_hdl = false;
630+
is_set_hdl_ = false;
631631

632-
if (!is_set_hdl) {
632+
if (!is_set_hdl_) {
633633
hdl_trans_states_.clear();
634634
hdl_gpio_sensor_states_.clear();
635635
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
@@ -685,7 +685,7 @@ bool DynamixelHardware::InitDxlReadItems()
685685
hdl_gpio_sensor_states_.push_back(temp_sensor);
686686
}
687687
}
688-
is_set_hdl = true;
688+
is_set_hdl_ = true;
689689
}
690690
for (auto it : hdl_trans_states_) {
691691
if (dxl_comm_->SetDxlReadItems(
@@ -704,9 +704,9 @@ bool DynamixelHardware::InitDxlReadItems()
704704
bool DynamixelHardware::InitDxlWriteItems()
705705
{
706706
RCLCPP_INFO_STREAM(logger_, "$$$$$ Init Dxl Write Items");
707-
static bool is_set_hdl = false;
707+
is_set_hdl_ = false;
708708

709-
if (!is_set_hdl) {
709+
if (!is_set_hdl_) {
710710
hdl_trans_commands_.clear();
711711
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
712712
if (gpio.command_interfaces.size()) {
@@ -728,7 +728,7 @@ bool DynamixelHardware::InitDxlWriteItems()
728728
hdl_trans_commands_.push_back(temp_write);
729729
}
730730
}
731-
is_set_hdl = true;
731+
is_set_hdl_ = true;
732732
}
733733

734734
for (auto it : hdl_trans_commands_) {

0 commit comments

Comments
 (0)