Skip to content

Segmentation fault in DynamixelDriver destructor #371

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Closed
tndrd opened this issue Apr 11, 2023 · 2 comments
Closed

Segmentation fault in DynamixelDriver destructor #371

tndrd opened this issue Apr 11, 2023 · 2 comments
Assignees

Comments

@tndrd
Copy link

tndrd commented Apr 11, 2023

Hello! I've been debugging my code that uses DynamixelDriver. I've found out that DynamixelDriver destructor causes segmentation fault in this case:

void foo()
{
  /* some code here */
  auto driver = std::make_shared<DynamixelDriver>();
  if (some_condition) return; // Segfault appears if this condition is satisfied
   
  /* some code here */
  driver->init(device_file.c_str(), uint32_t(baudrate))
  /* some code here */ 
}

My stack trace shows that segfault appears in destructor:

[starkit_ros_control-1] #0    Object "/home/root/workspace/install/dynamixel_workbench_toolbox/lib/libdynamixel_workbench_toolbox.so", at 0x7f2ef4ea9923, in DynamixelDriver::~DynamixelDriver()
[starkit_ros_control-1] Segmentation fault (Address not mapped to object [(nil)])

I've looked at DynamixelDriver source code. The destructor dereferences null pointer if DynamixelDriver::init() method has not been called somewhere before destruction. Here's a code snippet. Explanation in comments:

// dynamixel_driver.cpp

/* Constructor leaves portHandler_ pointer undefined (it is defined as dynamixel::PortHandler   *portHandler_) */

DynamixelDriver::DynamixelDriver() : tools_cnt_(0), 
                                    sync_write_handler_cnt_(0), 
                                    sync_read_handler_cnt_(0),
                                    bulk_read_parameter_cnt_(0)
{

}

/* Destructor doesn't check portHandler_ before dereferencing it, so segfault occures */

DynamixelDriver::~DynamixelDriver()
{ 
  for (int i = 0; i < tools_cnt_; i++)
  {
    for (int j = 0; j < tools_[i].getDynamixelCount(); j++)
    {
      writeRegister(tools_[i].getID()[j], "Torque_Enable", (uint8_t)0);
    }
  }

  portHandler_->closePort(); // Segfault occures here if portHandler_ has not been set yet
}

It seems like the bug may be fixed by simple null-pointer check before access.

Have a nice day!

@yun-goon yun-goon self-assigned this Jan 21, 2025
@yun-goon
Copy link
Contributor

Hi @tndrd
Sorry for the delayed response.

I believe that exception handling should only be supplementary, and it is most important to design the code in a way that ensures the destructor is not executed before initialization after the object is declared.

I will consider adding exception handling as a secondary measure. Thank you for your feedback.

@tndrd
Copy link
Author

tndrd commented Jan 21, 2025

Hi @yun-goon, thanks for replying.

I get your point. I suppose I'd close the issue, because we'd fixed the described behaviour a long time ago.

Good luck!

@tndrd tndrd closed this as completed Jan 21, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants