21 namespace protocol_layer
36 , control_client_(control_msg_callback,
37 control_error_callback,
38 config_.hostUDPPortControl(),
40 config_.scannerControlPort())
41 , data_client_(data_msg_callback,
43 config_.hostUDPPortData(),
45 config_.scannerDataPort())
46 , scanner_started_callback_(scanner_started_callback)
47 , scanner_stopped_callback_(scanner_stopped_callback)
48 , start_error_callback_(start_error_callback)
49 , stop_error_callback_(stop_error_callback)
50 , inform_user_about_laser_scan_callback_(laser_scan_callback)
51 , start_timeout_callback_(start_timeout_callback)
52 , monitoring_frame_timeout_callback_(monitoring_frame_timeout_callback)
59 #define DEFAULT_ON_ENTRY_IMPL(state_name)\ 60 template <class Event, class FSM>\ 61 void ScannerProtocolDef::state_name::on_entry(Event const&, FSM& fsm)\ 63 PSENSCAN_DEBUG("StateMachine", "Entering state: " #state_name);\ 66 #define DEFAULT_ON_EXIT_IMPL(state_name)\ 67 template <class Event, class FSM>\ 68 void ScannerProtocolDef::state_name::on_exit(Event const&, FSM& fsm)\ 70 PSENSCAN_DEBUG("StateMachine", "Exiting state: " #state_name);\ 73 #define DEFAULT_STATE_IMPL(state_name)\ 74 DEFAULT_ON_ENTRY_IMPL(state_name)\ 75 DEFAULT_ON_EXIT_IMPL(state_name) 83 template <
class Event,
class FSM>
84 void ScannerProtocolDef::Idle::on_exit(Event
const& , FSM& fsm)
87 fsm.control_client_.startAsyncReceiving();
88 fsm.data_client_.startAsyncReceiving();
91 template <
class Event,
class FSM>
92 void ScannerProtocolDef::WaitForStartReply::on_entry(Event
const& , FSM& fsm)
94 PSENSCAN_DEBUG(
"StateMachine",
"Entering state: WaitForStartReply");
96 fsm.start_reply_watchdog_ = fsm.watchdog_factory_.create(
WATCHDOG_TIMEOUT, fsm.start_timeout_callback_);
99 template <
class Event,
class FSM>
100 void ScannerProtocolDef::WaitForStartReply::on_exit(Event
const& , FSM& fsm)
102 PSENSCAN_DEBUG(
"StateMachine",
"Exiting state: WaitForStartReply");
104 fsm.start_reply_watchdog_.reset();
107 template <
class Event,
class FSM>
108 void ScannerProtocolDef::WaitForMonitoringFrame::on_entry(Event
const& , FSM& fsm)
110 PSENSCAN_DEBUG(
"StateMachine",
"Entering state: WaitForMonitoringFrame");
111 fsm.scan_buffer_.reset();
113 fsm.monitoring_frame_watchdog_ =
114 fsm.watchdog_factory_.create(
WATCHDOG_TIMEOUT, fsm.monitoring_frame_timeout_callback_);
117 template <
class Event,
class FSM>
118 void ScannerProtocolDef::WaitForMonitoringFrame::on_exit(Event
const& , FSM& fsm)
120 PSENSCAN_DEBUG(
"StateMachine",
"Exiting state: WaitForMonitoringFrame");
122 fsm.monitoring_frame_watchdog_.reset();
125 template <
class Event,
class FSM>
126 void ScannerProtocolDef::Stopped::on_entry(Event
const& , FSM& )
148 PSENSCAN_INFO(
"StateMachine",
"No host ip set! Using local ip: {}", host_ip.to_string());
156 PSENSCAN_DEBUG(
"StateMachine",
"Action: handleStartRequestTimeout");
158 "Timeout while waiting for the scanner to start! Retrying... " 159 "(Please check the ethernet connection or contact PILZ support if the error persists.)");
206 *(reply_event.
data_)) };
208 fmt::format(
"Unknown result code {:#04x} in start reply.", static_cast<uint32_t>(msg.result())));
219 *(reply_event.
data_)) };
220 stop_error_callback_(fmt::format(
"Unknown result code {:#04x} in stop reply.", static_cast<uint32_t>(msg.result())));
270 const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
288 const std::vector<data_conversion_layer::monitoring_frame::MessageStamped>& stamped_msgs)
290 if (std::all_of(stamped_msgs.begin(), stamped_msgs.end(), [](
const auto& stamped_msg) {
291 return stamped_msg.msg_.measurements().empty();
294 PSENSCAN_DEBUG(
"StateMachine",
"No measurement data in current monitoring frame(s), skipping laser scan callback.");
302 PSENSCAN_DEBUG(
"StateMachine",
"Action: handleMonitoringFrameTimeout");
305 "Timeout while waiting for MonitoringFrame message." 306 " (Please check the ethernet connection or contact PILZ support if the error persists.)");
313 :
std::runtime_error(error_msg)
342 *(reply_event.
data_)) };
349 *(reply_event.
data_)) };
356 *(reply_event.
data_)) };
363 *(reply_event.
data_)) };
370 *(reply_event.
data_)) };
377 *(reply_event.
data_)) };
411 using recursive_transition_table =
typename boost::msm::back::recursive_get_transition_table<FSM>::type;
412 using states =
typename boost::msm::back::generate_state_set<recursive_transition_table>::type;
414 std::string mangle_state_name;
415 boost::mpl::for_each<states, boost::msm::wrap<boost::mpl::placeholders::_1> >(
416 boost::msm::back::get_state_name<recursive_transition_table>(mangle_state_name, state_id));
417 const auto full_name{ boost::core::demangle(mangle_state_name.c_str()) };
418 return full_name.substr(full_name.rfind(
"::") + 2);
424 const auto full_name{ boost::core::demangle(
typeid(t).name()) };
425 return full_name.substr(full_name.rfind(
"::") + 2);
429 template <
class FSM,
class Event>
432 PSENSCAN_ERROR(
"StateMachine",
"Received error \"{}\". Shutting down now.", exception.what());
438 template <
class FSM,
class Event>
442 "No transition in state \"{}\" for event \"{}\".",
443 getStateName<FSM>(state),
452 PSENSCAN_WARN(
"StateMachine",
"Received monitoring frame despite not waiting for it");
#define DEFAULT_ON_EXIT_IMPL(state_name)
bool isRefusedStartReply(scanner_events::RawReplyReceived const &reply_event)
static LaserScan toLaserScan(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msgs)
Converts monitoring_frames of a scan_round to the user friendly LaserScan type sent by the IScanner::...
InternalScannerReplyError(const std::string &error_msg)
void notifyUserAboutRefusedStartReply(scanner_events::RawReplyReceived const &reply_event)
std::function< void(const std::string &)> ErrorCallback
bool isStartReply(data_conversion_layer::scanner_reply::Message const &msg)
Higher level data type representing a single monitoring frame.
std::vector< diagnostic::Message > diagnosticMessages() const
void checkForDiagnosticErrors(const data_conversion_layer::monitoring_frame::Message &msg)
#define PSENSCAN_WARN(name,...)
std::function< void(const data_conversion_layer::RawDataConstPtr &, const std::size_t &, const int64_t ×tamp)> NewMessageCallback
Exception thrown if an additional field was missing during deserialization of a Message.
const std::size_t num_bytes_
bool isAcceptedStartReply(scanner_events::RawReplyReceived const &reply_event)
void informUserAboutTheScanData(const data_conversion_layer::monitoring_frame::MessageStamped &stamped_msg)
std::function< void()> ScannerStartedCallback
std::function< void(const LaserScan &)> InformUserAboutLaserScanCallback
monitoring_frame::Message deserialize(const data_conversion_layer::RawData &data, const std::size_t &num_bytes)
uint8_t activeZoneset() const
bool isRefusedReply(data_conversion_layer::scanner_reply::Message const &msg)
void checkForChangedActiveZoneset(const data_conversion_layer::monitoring_frame::Message &msg)
void checkForInternalErrors(const data_conversion_layer::scanner_reply::Message &msg)
bool isUnknownReply(data_conversion_layer::scanner_reply::Message const &msg)
Contains the events needed to define and implement the scanner protocol.
RawData serialize(const data_conversion_layer::start_request::Message &start_request, const uint32_t &seq_number=DEFAULT_SEQ_NUMBER)
std::function< void()> TimeoutCallback
communication_layer::UdpClientImpl data_client_
static std::string getStateName(const int &state_id)
const ScannerStoppedCallback scanner_stopped_callback_
#define PSENSCAN_WARN_THROTTLE(period, name,...)
void stop()
Stops the underlying io_service so that no messages are received anymore.
const StartErrorCallback start_error_callback_
#define DEFAULT_ON_ENTRY_IMPL(state_name)
const StopErrorCallback stop_error_callback_
#define PSENSCAN_DEBUG(name,...)
void sendStartRequest(const T &event)
const data_conversion_layer::RawDataConstPtr data_
Higher level data type storing the configuration details of the scanner like scanner IP...
const ScannerStartedCallback scanner_started_callback_
void handleMonitoringFrame(const scanner_events::RawMonitoringFrameReceived &event)
Wrapping class for a Message and its corresponding timestamp.
Message deserialize(const data_conversion_layer::RawData &data)
void no_transition(Event const &event, FSM &, int state)
const data_conversion_layer::RawDataConstPtr data_
#define PSENSCAN_INFO(name,...)
std::unique_ptr< util::Watchdog > monitoring_frame_watchdog_
Timeout while waiting for MonitoringFrame.
const InformUserAboutLaserScanCallback inform_user_about_laser_scan_callback_
void handleStartRequestTimeout(const scanner_events::StartTimeout &event)
void write(const data_conversion_layer::RawData &data)
Asynchronously sends the specified data to the other endpoint.
static std::string classNameShort(const T &t)
Root namespace in which the software components to communicate with the scanner (firmware-version: 2)...
Received Start- or Stop-Reply message from scanner device.
bool isUnknownStopReply(scanner_events::RawReplyReceived const &reply_event)
boost::asio::ip::address_v4 hostIp()
Returns local ip address of current socket connection.
void sendStopRequest(const T &event)
#define PSENSCAN_ERROR(name,...)
bool isAcceptedStopReply(scanner_events::RawReplyReceived const &reply_event)
void add(const data_conversion_layer::monitoring_frame::MessageStamped &stamped_msg)
Adds the message to the current scan round.
boost::optional< uint32_t > hostIp() const
std::vector< data_conversion_layer::monitoring_frame::MessageStamped > currentRound()
communication_layer::UdpClientImpl control_client_
Timeout while waiting for scanner device to start.
constexpr OperationResult result() const
static constexpr std::chrono::milliseconds WATCHDOG_TIMEOUT
bool framesContainMeasurements(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msg)
: Exception thrown if data received from the scanner hardware could not be processed according to pro...
void notifyUserAboutUnknownStopReply(scanner_events::RawReplyReceived const &reply_event)
bool fragmentedScansEnabled() const
void notifyUserAboutStart(scanner_events::RawReplyReceived const &reply_event)
void notifyUserAboutUnknownStartReply(scanner_events::RawReplyReceived const &reply_event)
void handleMonitoringFrameTimeout(const scanner_events::MonitoringFrameTimeout &event)
Exception indicating problems with the monitoring frames of a scan round.
bool isStopReply(data_conversion_layer::scanner_reply::Message const &msg)
uint32_t scanCounter() const
ScannerConfiguration config_
void sendMessageWithMeasurements(const std::vector< data_conversion_layer::monitoring_frame::MessageStamped > &stamped_msg)
std::function< void()> ScannerStoppedCallback
Higher level data type representing a scanner start request.
std::string formatRange(const T &range)
bool isUnknownStartReply(scanner_events::RawReplyReceived const &reply_event)
constexpr Type type() const
ScannerProtocolDef(const ScannerConfiguration &config, const communication_layer::NewMessageCallback &control_msg_callback, const communication_layer::ErrorCallback &control_error_callback, const communication_layer::ErrorCallback &start_error_callback, const communication_layer::ErrorCallback &stop_error_callback, const communication_layer::NewMessageCallback &data_msg_callback, const communication_layer::ErrorCallback &data_error_callback, const ScannerStartedCallback &scanner_started_callback, const ScannerStoppedCallback &scanner_stopped_callback, const InformUserAboutLaserScanCallback &laser_scan_callback, const TimeoutCallback &start_timeout_callback, const TimeoutCallback &monitoring_frame_timeout_callback)
boost::optional< data_conversion_layer::monitoring_frame::Message > zoneset_reference_msg_
void exception_caught(Event const &event, FSM &fsm, std::exception &exception)
void notifyUserAboutStop(scanner_events::RawReplyReceived const &reply_event)
Higher level data type representing a reply message from the scanner.
bool isRefusedStopReply(scanner_events::RawReplyReceived const &reply_event)
void notifyUserAboutRefusedStopReply(scanner_events::RawReplyReceived const &reply_event)
bool isAcceptedReply(data_conversion_layer::scanner_reply::Message const &msg)
#define DEFAULT_STATE_IMPL(state_name)
Received monitoring frame from scanner device.
bool hasDiagnosticMessagesField() const