Skip to content
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

std::exception::what: Duration is out of dual 32-bit range #449

Open
fzoric8 opened this issue Dec 14, 2021 · 9 comments
Open

std::exception::what: Duration is out of dual 32-bit range #449

fzoric8 opened this issue Dec 14, 2021 · 9 comments
Assignees

Comments

@fzoric8
Copy link

fzoric8 commented Dec 14, 2021

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.

@fzoric8
Copy link
Author

fzoric8 commented Dec 15, 2021

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.

@fzoric8
Copy link
Author

fzoric8 commented Jan 12, 2022

It would be great to find out how to debug write or read method. Thanks :)

@OTL
Copy link

OTL commented Jan 17, 2022

We have the same issue on Ubuntu20.04, noetic.

@mathias-luedtke
Copy link
Member

mathias-luedtke commented Jan 17, 2022

@ipa-hsd: Please try to confirm this issue with noetic.

@mathias-luedtke
Copy link
Member

@fzoric8, @OTL: This sounds similar to moveit/moveit#1062

@fzoric8
Copy link
Author

fzoric8 commented Jan 17, 2022

@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.

@mathias-luedtke
Copy link
Member

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?

if(!nh_.param("use_realtime_period", false)){
dur.fromSec(boost::chrono::duration<double>(update_duration_).count());
ROS_INFO_STREAM("Using fixed control period: " << dur);
}else{
ROS_INFO("Using real-time control period");
}

@fzoric8
Copy link
Author

fzoric8 commented Jan 18, 2022

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.

@miguelprada
Copy link
Member

May also be related to ros-controls/ros_controllers#577.

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

5 participants