Skip to content

Commit d8ca2e6

Browse files
Feature/status (#22)
* (wip) start on status monitoring * use json serialization and fix rate * actually log inference information * minor style fixes
1 parent 006b1ab commit d8ca2e6

File tree

3 files changed

+111
-0
lines changed

3 files changed

+111
-0
lines changed

semantic_inference_ros/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ find_package(cv_bridge REQUIRED)
1717
find_package(ianvs REQUIRED)
1818
find_package(image_geometry REQUIRED)
1919
find_package(message_filters REQUIRED)
20+
find_package(nlohmann_json REQUIRED)
2021
find_package(rclcpp REQUIRED)
2122
find_package(rclcpp_components REQUIRED)
2223
find_package(rosbag2_transport REQUIRED)
@@ -46,6 +47,7 @@ target_link_libraries(
4647
ianvs::ianvs
4748
image_geometry::image_geometry
4849
message_filters::message_filters
50+
nlohmann_json::nlohmann_json
4951
rclcpp_components::component
5052
tf2_eigen::tf2_eigen
5153
tf2_ros::tf2_ros

semantic_inference_ros/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
<depend>ianvs</depend>
1717
<depend>image_geometry</depend>
1818
<depend>message_filters</depend>
19+
<depend>nlohmann-json-dev</depend>
1920
<depend>rclcpp</depend>
2021
<depend>rclcpp_components</depend>
2122
<depend>rosbag2_transport</depend>

semantic_inference_ros/src/segmentation_nodelet.cpp

Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,13 +37,16 @@
3737
#include <semantic_inference/segmenter.h>
3838

3939
#include <atomic>
40+
#include <chrono>
4041
#include <mutex>
4142
#include <optional>
4243
#include <thread>
4344

4445
#include <cv_bridge/cv_bridge.hpp>
46+
#include <nlohmann/json.hpp>
4547
#include <opencv2/core.hpp>
4648
#include <rclcpp/node.hpp>
49+
#include <std_msgs/msg/string.hpp>
4750

4851
#include "semantic_inference_ros/output_publisher.h"
4952
#include "semantic_inference_ros/ros_log_sink.h"
@@ -63,6 +66,12 @@ class SegmentationNode : public rclcpp::Node {
6366
ImageRotator::Config image_rotator;
6467
bool show_config = true;
6568
bool show_output_config = false;
69+
struct Status {
70+
std::string nickname = "semantic_inference";
71+
size_t rate_window_size = 10;
72+
double period_s = 0.5;
73+
double max_heartbeat_s = 10.0;
74+
} status;
6675
} const config;
6776

6877
explicit SegmentationNode(const rclcpp::NodeOptions& options);
@@ -73,14 +82,40 @@ class SegmentationNode : public rclcpp::Node {
7382
private:
7483
void runSegmentation(const Image::ConstSharedPtr& msg);
7584

85+
void recordStatus(double elapsed_s, const std::string& error = "");
86+
87+
void publishStatus();
88+
7689
std::unique_ptr<Segmenter> segmenter_;
7790
std::unique_ptr<ImageWorker> worker_;
7891

92+
std::mutex status_mutex_;
93+
std::optional<rclcpp::Time> last_call_;
94+
std::string last_status_;
95+
std::list<double> elapsed_samples_s_;
96+
97+
rclcpp::TimerBase::SharedPtr timer_;
98+
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr status_pub_;
99+
79100
OutputPublisher output_pub_;
80101
ImageRotator image_rotator_;
81102
ianvs::ImageSubscription sub_;
82103
};
83104

105+
void declare_config(SegmentationNode::Config::Status& config) {
106+
using namespace config;
107+
name("SegmentationNode::Config");
108+
field(config.nickname, "nickname");
109+
field(config.rate_window_size, "rate_window_size");
110+
field(config.period_s, "period_s");
111+
field(config.max_heartbeat_s, "max_heartbeat_s");
112+
113+
checkCondition(!config.nickname.empty(), "nickname is empty");
114+
check(config.rate_window_size, GT, 0, "rate_window_size");
115+
check(config.period_s, GT, 0.0, "period_s");
116+
check(config.max_heartbeat_s, GT, 0.0, "max_heartbeat_s");
117+
}
118+
84119
void declare_config(SegmentationNode::Config& config) {
85120
using namespace config;
86121
name("SegmentationNode::Config");
@@ -89,6 +124,7 @@ void declare_config(SegmentationNode::Config& config) {
89124
field(config.image_rotator, "image_rotator");
90125
field(config.show_config, "show_config");
91126
field(config.show_output_config, "show_output_config");
127+
field(config.status, "status");
92128
}
93129

94130
SegmentationNode::SegmentationNode(const rclcpp::NodeOptions& options)
@@ -126,6 +162,12 @@ SegmentationNode::SegmentationNode(const rclcpp::NodeOptions& options)
126162

127163
sub_.registerCallback(&ImageWorker::addMessage, worker_.get());
128164
sub_.subscribe("color/image_raw");
165+
166+
const auto period_ms = std::chrono::duration_cast<std::chrono::milliseconds>(
167+
std::chrono::duration<double>(config.status.period_s));
168+
status_pub_ = create_publisher<std_msgs::msg::String>("~/status", rclcpp::QoS(1));
169+
timer_ =
170+
create_wall_timer(period_ms, std::bind(&SegmentationNode::publishStatus, this));
129171
}
130172

131173
SegmentationNode::~SegmentationNode() {
@@ -140,6 +182,7 @@ void SegmentationNode::runSegmentation(const Image::ConstSharedPtr& msg) {
140182
img_ptr = cv_bridge::toCvShare(msg, "rgb8");
141183
} catch (const cv_bridge::Exception& e) {
142184
SLOG(ERROR) << "cv_bridge exception: " << e.what();
185+
recordStatus(0.0, "Conversion error: " + std::string(e.what()));
143186
return;
144187
}
145188

@@ -148,15 +191,80 @@ void SegmentationNode::runSegmentation(const Image::ConstSharedPtr& msg) {
148191
<< " is right type? "
149192
<< (img_ptr->image.type() == CV_8UC3 ? "yes" : "no");
150193

194+
const auto start = std::chrono::steady_clock::now();
151195
const auto rotated = image_rotator_.rotate(img_ptr->image);
152196
const auto result = segmenter_->infer(rotated);
153197
if (!result) {
154198
SLOG(ERROR) << "failed to run inference!";
199+
recordStatus(0.0, "Failed to run inference");
155200
return;
156201
}
157202

158203
const auto derotated = image_rotator_.derotate(result.labels);
159204
output_pub_.publish(img_ptr->header, derotated, img_ptr->image);
205+
const auto end = std::chrono::steady_clock::now();
206+
207+
const auto elapsed =
208+
std::chrono::duration_cast<std::chrono::duration<double>>(end - start);
209+
recordStatus(elapsed.count());
210+
}
211+
212+
void SegmentationNode::recordStatus(double elapsed_s, const std::string& error) {
213+
std::lock_guard<std::mutex> lock(status_mutex_);
214+
last_call_ = now();
215+
last_status_ = error;
216+
if (!error.empty()) {
217+
return;
218+
}
219+
220+
elapsed_samples_s_.push_back(elapsed_s);
221+
if (elapsed_samples_s_.size() > config.status.rate_window_size) {
222+
elapsed_samples_s_.pop_front();
223+
}
224+
}
225+
226+
void SegmentationNode::publishStatus() {
227+
std::lock_guard<std::mutex> lock(status_mutex_);
228+
std::chrono::nanoseconds curr_time_ns(now().nanoseconds());
229+
230+
nlohmann::json record;
231+
record["nickname"] = config.status.nickname;
232+
record["node_name"] = get_fully_qualified_name();
233+
if (!last_call_) {
234+
record["status"] = "WARNING";
235+
record["note"] = "Waiting for input";
236+
} else {
237+
const auto diff = now() - *last_call_;
238+
if (diff.seconds() > config.status.max_heartbeat_s) {
239+
record["status"] = "ERROR";
240+
std::stringstream ss;
241+
ss << "No input processed in " << diff.seconds() << " s";
242+
record["note"] = ss.str();
243+
} else if (!last_status_.empty()) {
244+
record["status"] = "ERROR";
245+
record["note"] = last_status_;
246+
} else {
247+
double average_elapsed_s = 0.0;
248+
for (const auto sample : elapsed_samples_s_) {
249+
average_elapsed_s += sample;
250+
}
251+
if (elapsed_samples_s_.size()) {
252+
average_elapsed_s /= elapsed_samples_s_.size();
253+
}
254+
255+
record["status"] = "NOMINAL";
256+
std::stringstream ss;
257+
ss << "Average elapsed time: " << average_elapsed_s << " s";
258+
record["note"] = ss.str();
259+
}
260+
}
261+
262+
std::stringstream ss;
263+
ss << record;
264+
265+
auto msg = std::make_unique<std_msgs::msg::String>();
266+
msg->data = ss.str();
267+
status_pub_->publish(std::move(msg));
160268
}
161269

162270
} // namespace semantic_inference

0 commit comments

Comments
 (0)