ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | Q&A answers.ros.org |
![]() | 1 | initial version |
For the future reader: Yes, all of the above are confirmed.
struct A {
ros::NodeHandle n;
ros::Publisher pub;
ros::Subscriber sub;
A() {
boost::function<void(const std_msgs::StringConstPtr &)> func = [](const std_msgs::StringConstPtr &msg) {
std::cerr << "CALLBACK STARTED...waiting 3 seconds\n";
std::this_thread::sleep_for(std::chrono::seconds(3));
std::cerr << "CALLBACK FINISHED!!!\n";
};
pub = n.advertise<std_msgs::String>("bah", 10, false);
sub = n.subscribe("bah", 10, func);
}
};
int main(int argc, char **argv) {
std::cerr << "STARTED\n";
ros::init(argc, argv, "tokens_system_test");
ros::Time::init();
{
A *a = new A;
int start = 100000;
int count = start;
ros::AsyncSpinner spinner(0);
spinner.start();
while (ros::ok() && --count) {
if (count == start - 1) {
std::cerr << "Publishing message\n";
std_msgs::String msg;
a->pub.publish(msg);
}
if (count == start / 2) {
std::cerr << "Deleting a...\n";
delete a;
a = nullptr;
std::cerr << "Deleting a FINISHED####\n";
}
}
spinner.stop();
}
And this prints:
STARTED
Publishing message
CALLBACK STARTED...waiting 3 seconds
Deleting a... (blocks for 3 seconds!)
CALLBACK FINISHED!!!
Deleting a FINISHED####
![]() | 2 | No.2 Revision |
For the future reader: Yes, all of the above are confirmed.
struct B {
int b = 1111;
~B() {
b = 0; /* clear memory */
std::cerr << "B is destroyed!\n";
}
};
struct A {
ros::NodeHandle n;
ros::Publisher pub;
ros::Subscriber sub;
B b;
A() {
boost::function<void(const std_msgs::StringConstPtr &)> func = [](const [this](const std_msgs::StringConstPtr &msg) {
std::cerr << "CALLBACK "B=" << b.b << " CALLBACK STARTED...waiting 3 seconds\n";
std::this_thread::sleep_for(std::chrono::seconds(3));
std::cerr << "CALLBACK "B=" << b.b << " CALLBACK FINISHED!!!\n";
};
pub = n.advertise<std_msgs::String>("bah", 10, false);
sub = n.subscribe("bah", 10, func);
}
};
int main(int argc, char **argv) {
std::cerr << "STARTED\n";
ros::init(argc, argv, "tokens_system_test");
"a_blah");
ros::Time::init();
{
A *a = new A;
int start = 100000;
int count = start;
ros::AsyncSpinner spinner(0);
spinner.start();
while (ros::ok() && --count) {
if (count == start - 1) {
std::cerr << "Publishing message\n";
std_msgs::String msg;
a->pub.publish(msg);
}
if (count == start / 2) {
std::cerr << "Deleting a...\n";
delete a;
a = nullptr;
std::cerr << "Deleting a FINISHED####\n";
}
}
spinner.stop();
}
And this prints:
STARTED
Publishing message
B=1111 CALLBACK STARTED...waiting 3 seconds
Deleting a... (blocks for 3 seconds!)
a...
B is destroyed!
B=0 CALLBACK FINISHED!!!
Deleting a FINISHED####
![]() | 3 | No.3 Revision |
For the future reader: Yes, all of the above are confirmed.
struct B {
int b = 1111;
~B() {
b = 0; /* clear memory */
std::cerr << "B is destroyed!\n";
}
};
struct A {
ros::NodeHandle n;
ros::Publisher pub;
ros::Subscriber sub;
B b;
A() {
boost::function<void(const std_msgs::StringConstPtr &)> func = [this](const std_msgs::StringConstPtr &msg) {
std::cerr << "B=" << b.b << " CALLBACK STARTED...waiting 3 seconds\n";
std::this_thread::sleep_for(std::chrono::seconds(3));
std::cerr << "B=" << b.b << " CALLBACK FINISHED!!!\n";
};
pub = n.advertise<std_msgs::String>("bah", 10, false);
sub = n.subscribe("bah", 10, func);
}
};
int main(int argc, char **argv) {
std::cerr << "STARTED\n";
ros::init(argc, argv, "a_blah");
ros::Time::init();
{
A *a = new A;
int start = 100000;
int count = start;
ros::AsyncSpinner spinner(0);
spinner.start();
while (ros::ok() && --count) {
if (count == start - 1) {
std::cerr << "Publishing message\n";
std_msgs::String msg;
a->pub.publish(msg);
}
if (count == start / 2) {
std::cerr << "Deleting a...\n";
delete a;
a = nullptr;
std::cerr << "Deleting a FINISHED####\n";
}
}
spinner.stop();
}
And this prints:
STARTED
Publishing message
B=1111 CALLBACK STARTED...waiting 3 seconds
Deleting a...
a... <<<BLOCKS FOR ~3 SECONDS>>>
B is destroyed!
B=0 CALLBACK FINISHED!!!
Deleting a FINISHED####
![]() | 4 | No.4 Revision |
For the future reader: Yes, all of the above are confirmed.
struct B {
int b = 1111;
~B() {
b = 0; /* clear memory */
std::cerr << "B is destroyed!\n";
}
};
struct A {
ros::NodeHandle n;
ros::Publisher pub;
ros::Subscriber sub;
B b;
A() {
boost::function<void(const std_msgs::StringConstPtr &)> func = [this](const std_msgs::StringConstPtr &msg) {
std::cerr << "B=" << b.b << " CALLBACK STARTED...waiting 3 seconds\n";
std::this_thread::sleep_for(std::chrono::seconds(3));
std::cerr << "B=" << b.b << " CALLBACK FINISHED!!!\n";
};
pub = n.advertise<std_msgs::String>("bah", 10, false);
sub = n.subscribe("bah", 10, func);
}
};
int main(int argc, char **argv) {
std::cerr << "STARTED\n";
ros::init(argc, argv, "a_blah");
ros::Time::init();
{
A *a = new A;
int start = 100000;
int count = start;
ros::AsyncSpinner spinner(0);
spinner.start();
while (ros::ok() && --count) {
if (count == start - 1) {
std::cerr << "Publishing message\n";
std_msgs::String msg;
a->pub.publish(msg);
}
if (count == start / 2) {
std::cerr << "Deleting a...\n";
delete a;
a = nullptr;
std::cerr << "Deleting a FINISHED####\n";
}
}
spinner.stop();
}
And this prints:
STARTED
Publishing message
B=1111 CALLBACK STARTED...waiting 3 seconds
Deleting a...
B is destroyed!
<<<BLOCKS FOR ~3 SECONDS>>>
B is destroyed!
B=0 CALLBACK FINISHED!!!
Deleting a FINISHED####