std::exception::what: Duration is out of dual 32-bit range
fzoric8 opened this issue ยท 9 comments
I'm using canopen_motor_node
as my driver for Schunk LWA4p
robotic arm.
Sometimes after sending motion plan to robot trajectory controller which uses ros control and mentioned driver to send motor commands over CAN to robot joints.
Most of the time, everything executes correctly, however, sometimes I get following error:
[ERROR] [1639496142.557002552] [/lwa4p/driver]: Dynamic exception type: std::runtime_error
std::exception::what: Duration is out of dual 32-bit range
And I'm not sure what can cause it.
In meantime I will try to build ros_canopen
from source, and my environment is:
- Ubuntu 20.04
- ROS noetic
- SocketCAN driver
- Docker version 20.10.3, build 48d30b5
Any help would be appreciated. Thank you very much.
I narrowed it down to following method:
[ERROR] [1639561818.689072706] [/lwa4p/driver] [/home/developer/moveit_ws/src/ros_canopen/canopen_chain_node/src/ros_chain.cpp] [7fe035ffb700] [RosChain::run]: Dynamic exception type: std::runtime_error
std::exception::what: Duration is out of dual 32-bit range
Which is:
running_ = true;
time_point abs_time = boost::chrono::high_resolution_clock::now();
while(running_){
LayerStatus s;
try{
//ROS_INFO_STREAM_THROTTLE("LayerStatus: " << s);
read(s);
write(s);
if(!s.bounded<LayerStatus::Warn>()) ROS_ERROR_STREAM_THROTTLE(10, s.reason());
else if(!s.bounded<LayerStatus::Ok>()) ROS_WARN_STREAM_THROTTLE(10, s.reason());
}
catch(const canopen::Exception& e){
ROS_ERROR_STREAM_THROTTLE(1, boost::diagnostic_information(e));
//ROS_INFO_STREM("Layer Status is: " << s);
//ROS_INFO_STREAM("abs_time: " << abs_time);
}
if(!sync_){
abs_time += update_duration_;
boost::this_thread::sleep_until(abs_time);
}
}
So it seems that read
or write
fail but I would like to debug this, or check what causes failure. Ty.
It would be great to find out how to debug write
or read
method. Thanks :)
We have the same issue on Ubuntu20.04, noetic.
@ipa-hsd: Please try to confirm this issue with noetic.
@fzoric8, @OTL: This sounds similar to moveit/moveit#1062
@fzoric8, @OTL: This sounds similar to moveit/moveit#1062
Hi, I've seen that issue before. After that I've rebuilt my catkin workspace but error still persists.
Above all, I'm using docker with new ros noetic as well as ros_canopen built from source. Still no luck, error persists. Therefore, I'm quite confident it's not due to the incompatible binaries.
My assumption in my case is that method read or write fail, and that causes this error although they're not related.
I'm using docker with new ros noetic as well as ros_canopen built from source
Not really a stable, well-defined system..
My assumption in my case is that method read or write fail, and that causes this error although they're not related.
The read/write functions are the core of ros_canopen and glue all the different layers.
And any unhandled execption gets caught here to prevent the ROS node from crashing.
But ros::Duration (where you exception is from) is only used for dealing with ros_control(lers).
If it is not an ABI break it could be a division by zero (or something similar) as well. You could try to get a stacktrace.
To rule out any problem with ros_canopen itself: What gets logged from the following code?
ros_canopen/canopen_motor_node/src/motor_chain.cpp
Lines 71 to 76 in eaaf0a1
Hi, out of curiosity, what would be defined as stable well-defined system?
You can see my docker configuration for particular problem here
Since ROS is open-source and we can use it on all sorts of different PCs, docker provides me well defined Linux environment, as well as backup if or when I introduce some ABI break.
I'm currently not able to try it out, but after mid-february I'll give it a try and let you know.
May also be related to ros-controls/ros_controllers#577.