@@ -627,9 +627,9 @@ bool DynamixelHardware::InitDxlItems()
627
627
bool DynamixelHardware::InitDxlReadItems ()
628
628
{
629
629
RCLCPP_INFO_STREAM (logger_, " $$$$$ Init Dxl Read Items" );
630
- static bool is_set_hdl = false ;
630
+ is_set_hdl_ = false ;
631
631
632
- if (!is_set_hdl ) {
632
+ if (!is_set_hdl_ ) {
633
633
hdl_trans_states_.clear ();
634
634
hdl_gpio_sensor_states_.clear ();
635
635
for (const hardware_interface::ComponentInfo & gpio : info_.gpios ) {
@@ -685,7 +685,7 @@ bool DynamixelHardware::InitDxlReadItems()
685
685
hdl_gpio_sensor_states_.push_back (temp_sensor);
686
686
}
687
687
}
688
- is_set_hdl = true ;
688
+ is_set_hdl_ = true ;
689
689
}
690
690
for (auto it : hdl_trans_states_) {
691
691
if (dxl_comm_->SetDxlReadItems (
@@ -704,9 +704,9 @@ bool DynamixelHardware::InitDxlReadItems()
704
704
bool DynamixelHardware::InitDxlWriteItems ()
705
705
{
706
706
RCLCPP_INFO_STREAM (logger_, " $$$$$ Init Dxl Write Items" );
707
- static bool is_set_hdl = false ;
707
+ is_set_hdl_ = false ;
708
708
709
- if (!is_set_hdl ) {
709
+ if (!is_set_hdl_ ) {
710
710
hdl_trans_commands_.clear ();
711
711
for (const hardware_interface::ComponentInfo & gpio : info_.gpios ) {
712
712
if (gpio.command_interfaces .size ()) {
@@ -728,7 +728,7 @@ bool DynamixelHardware::InitDxlWriteItems()
728
728
hdl_trans_commands_.push_back (temp_write);
729
729
}
730
730
}
731
- is_set_hdl = true ;
731
+ is_set_hdl_ = true ;
732
732
}
733
733
734
734
for (auto it : hdl_trans_commands_) {
0 commit comments