9 uint8_t ourSystemId, uint8_t ourComponentId, uint8_t systemId, uint8_t componentId)
10 : QObject(parent), _timer(parent),
11 _handleEventCB(handleEventCB),
12 _sendRequestCB(sendRequestCB),
15 auto error_cb = [componentId,
this](
int num_events_lost) {
16 _healthAndArmingChecks.reset();
17 qCWarning(EventsLog) <<
"Events got lost:" << num_events_lost <<
"comp_id:" << componentId;
20 auto timeout_cb = [
this](
int timeout_ms) {
24 _timer.setSingleShot(
true);
25 _timer.start(timeout_ms);
29 _parser.setProfile(profile.toStdString());
31 _parser.formatters().url = [](
const std::string& content,
const std::string& link) {
32 return "<a href=\""+link+
"\">"+content+
"</a>"; };
34 _parser.formatters().param = [](
const std::string& content) {
35 return "<a href=\"param://"+content+
"\">"+content+
"</a>"; };
37 _parser.formatters().escape = [](
const std::string& str) {
38 return QString::fromStdString(str).toHtmlEscaped().toStdString(); };
40 events::ReceiveProtocol::Callbacks callbacks{error_cb, _sendRequestCB,
41 std::bind(&EventHandler::gotEvent,
this, std::placeholders::_1), timeout_cb};
42 _protocol =
new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId, systemId, componentId);
44 connect(&_timer, &QTimer::timeout,
this, [
this]() { _protocol->timerEvent(); });
46 qRegisterMetaType<QSharedPointer<events::parser::ParsedEvent>>(
"ParsedEvent");
EventHandler(QObject *parent, const QString &profile, handle_event_f handleEventCB, send_request_event_message_f sendRequestCB, uint8_t ourSystemId, uint8_t ourComponentId, uint8_t systemId, uint8_t componentId)