You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Hello! I've been debugging my code that uses DynamixelDriver. I've found out that DynamixelDriver destructor causes segmentation fault in this case:
voidfoo()
{
/* 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!
The text was updated successfully, but these errors were encountered:
Hello! I've been debugging my code that uses DynamixelDriver. I've found out that DynamixelDriver destructor causes segmentation fault in this case:
My stack trace shows that segfault appears in destructor:
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:
It seems like the bug may be fixed by simple null-pointer check before access.
Have a nice day!
The text was updated successfully, but these errors were encountered: