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
I have an existing program that I am adding ros support to, and one of the requirements is that the program must be able to launch before the ros master and be able to connect afterwards. A simplified version of the connection code is below, which works except during shutdown.
The issue is that the program shuts down using a handler setup by a call to atexit(), which it sets up in the very beginning. This means that if the master does not connect till after the atexit() call then ros::start() is not called till after as well. It appears that parts of the ros_comm system (Specifically the TopicManager I think) do not get fully initialized until a call to ros::start() or a NodeHandle gets initialized. The atexit() handler gets called relative to when it got called vs when other static objects were initialized. This means that when the destruction happens at the end the static internal ros objects get destroyed before the atexit() handler gets called. This then causes the following crash when using a publisher.
terminate called after throwing an instance of 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
Aborted (core dumped)
A full code example that recreates the problem is here:
#include "ros/ros.h"
#include "std_msgs/Int32.h"
#include <thread>
#include <atomic>
static ros::Publisher pub;
static ros::NodeHandle* handle;
void shutdown()
{
//delay just to make sure destruction of other stuff happens, this isn't really needed though
usleep(1000);
// Publish out a message before we have finished shutting down
// This will crash here since static ros variables will be destructed
std_msgs::Int32 msg;
msg.data=1;
pub.publish(msg);
//do the actual shutdown
pub.shutdown();
handle->shutdown();
ros::shutdown();
std::cout << "Shutdown successful" <<std::endl;
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "test");
handle = nullptr;
// Register the shutdown function to be run after returning from main. This will be run AFTER parts of ROS are
// destructed since the master connects after this registration.
// Removing this call and using the one below works fine
atexit(shutdown);
while (!ros::master::check())
{
usleep(500);
}
std::cout << "Connected to master\n";
//Thread to let the wait for input without blocking
//Used so we don't need to ctrl-c to stop the ros node
std::atomic<bool> interrupted(false);
std::thread th([&]() {
std::string str;
while(str.empty())
std::cin >> str;
interrupted = true;
});
handle = new ros::NodeHandle();
pub = handle->advertise<std_msgs::Int32>("pub",1);
//calling atexit here works fine
//atexit(shutdown);
//Loop till we get input
while(!interrupted)
{
ros::spinOnce();
}
std::cout << "\nStopping" << std::endl;
th.join();
return 0;
}
It seems likely that this issue is related to issue #838
The text was updated successfully, but these errors were encountered:
I have an existing program that I am adding ros support to, and one of the requirements is that the program must be able to launch before the ros master and be able to connect afterwards. A simplified version of the connection code is below, which works except during shutdown.
The issue is that the program shuts down using a handler setup by a call to
atexit()
, which it sets up in the very beginning. This means that if the master does not connect till after theatexit()
call thenros::start()
is not called till after as well. It appears that parts of the ros_comm system (Specifically the TopicManager I think) do not get fully initialized until a call toros::start()
or aNodeHandle
gets initialized. Theatexit()
handler gets called relative to when it got called vs when other static objects were initialized. This means that when the destruction happens at the end the static internal ros objects get destroyed before theatexit()
handler gets called. This then causes the following crash when using a publisher.A full code example that recreates the problem is here:
It seems likely that this issue is related to issue #838
The text was updated successfully, but these errors were encountered: