Multiple bondcpp bonds between nodes
Hi,
what I want to achieve is to create system watchdog informing me when some of my nodes crash.
The problem is that the bonds cannot be created. Or at least they die after few seconds. When I test this in rqt_graph I can see the connections between my nodes and system watchdog established. But after a few seconds all bonds are broken for some reason. Is this the right way how to create list of bonds? Am I missing something?
Here's my example of such a watchdog:
std::string filename_;
std::vector<std::string> node_list_;
std::vector<std::shared_ptr<bond::Bond>> bonds_;
void initFilename() {
std::string home_directory = getenv("HOME");
if (home_directory.empty()) {
home_directory = getpwuid(getuid())->pw_dir;
}
filename_ = home_directory + "/aft_copter/src/aft_copter/aft_safety/config/node_list.txt";
}
void initNodeList() {
if (filename_.empty()) return;
std::ifstream file(filename_.c_str());
std::string text;
while (std::getline(file, text)) {
node_list_.push_back(text + "_bond");
}
}
void initBonds() {
if (node_list_.empty()) return;
bonds_.resize(node_list_.size());
int i{0};
for (auto&& node :node_list_) {
bonds_.at(i) = std::make_shared<bond::Bond>(node + "_topic", node);
bonds_.at(i)->start();
i++;
}
}
int main(int argc, char** argv) {
ros::init(argc, argv, "system_watchdog");
ros::NodeHandle nh;
initFilename();
initNodeList();
initBonds();
ros::Rate rate(20.0);
while (ros::ok()) {
ros::spinOnce();
rate.sleep();
}
return 0;
}
This code basically reads names of nodes saved in text file and creates bonds with those nodes. Then in those nodes I do something like this:
class PatternRecognitionAction {
public:
PatternRecognitionAction(){
initBond();
}
void initBond() {
std::string node_name = "pattern_recognition_action";
bond_ = std::make_shared<bond::Bond>(node_name + "_bond_topic",
node_name + "_bond");
bond_->start();
}
private:
std::shared_ptr<bond::Bond> bond_;
int main(int argc, char** argv) {
ros::init(argc, argv, "pattern_recognition");
PatternRecognitionAction pattern_recognition("pattern_recognition");
ros::spin();
ROS_INFO_STREAM("Ready to recognize pattern.");
return 0;
}
'node_name' is not defined in your lower example. You can reuse a topic for all bonds is defined by the topic AND the bond_name. How long are the nodes established? How many nodes do you connect with the central server? Is it possible that setting up all the bonds takes too long?
The node_name variable was not declared in my example, but in my original code it is defined. I've tried only 3 bonds, but even with 1 bond this example doesn't work. The strange thing is that when I look at bond_topic I can see messages coming there. But after 6 messages, bond is broken.