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

fix thread handling of node_status_publisher. #2058

Merged
merged 1 commit into from
Mar 6, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,8 @@ class NodeStatusPublisher {
void publishStatus();
bool node_activated_;
std::mutex mtx_;
boost::thread publish_thread_;
bool ros_ok_;
};
}
#endif // NODE_STATUS_PUBLISHER_H_INCLUDED
#endif // NODE_STATUS_PUBLISHER_H_INCLUDED
Original file line number Diff line number Diff line change
Expand Up @@ -23,17 +23,21 @@ namespace autoware_health_checker {
NodeStatusPublisher::NodeStatusPublisher(ros::NodeHandle nh,
ros::NodeHandle pnh) {
node_activated_ = false;
ros_ok_ = true;
nh_ = nh;
pnh_ = pnh;
status_pub_ =
nh_.advertise<autoware_system_msgs::NodeStatus>("node_status", 10);
}

NodeStatusPublisher::~NodeStatusPublisher() {}
NodeStatusPublisher::~NodeStatusPublisher() {
ros_ok_ = false;
publish_thread_.join();
}

void NodeStatusPublisher::publishStatus() {
ros::Rate rate = ros::Rate(autoware_health_checker::UPDATE_RATE);
while (ros::ok()) {
while (ros_ok_) {
mtx_.lock();
autoware_system_msgs::NodeStatus status;
status.node_activated = node_activated_;
Expand Down Expand Up @@ -70,8 +74,7 @@ void NodeStatusPublisher::publishStatus() {
}

void NodeStatusPublisher::ENABLE() {
boost::thread publish_thread(
boost::bind(&NodeStatusPublisher::publishStatus, this));
publish_thread_ = boost::thread(boost::bind(&NodeStatusPublisher::publishStatus, this));
return;
}

Expand Down Expand Up @@ -219,4 +222,4 @@ std::string NodeStatusPublisher::doubeToJson(double value) {
write_json(ss, pt);
return ss.str();
}
}
}