From a2cdca91663cffdd5c2870b357424d2ffe84d6a6 Mon Sep 17 00:00:00 2001 From: Adrian Del Grosso <10929341+ad3154@users.noreply.github.com> Date: Thu, 8 Feb 2024 19:49:31 -0700 Subject: [PATCH] Update AgIsoStack Updated the version of AgIsoStack++ to 867d2c0d02a31f97c17aab2d17970f650db1bf8e --- examples/VirtualTerminal/VirtualTerminal.ino | 8 +- library.properties | 2 +- src/AgIsoStack.hpp | 14 +- src/can_NAME_filter.cpp | 2 +- src/can_NAME_filter.hpp | 1 + src/can_address_claim_state_machine.hpp | 3 + src/can_callbacks.hpp | 10 + src/can_constants.hpp | 3 + src/can_control_function.hpp | 3 +- src/can_extended_transport_protocol.cpp | 1424 +-- src/can_extended_transport_protocol.hpp | 384 +- src/can_general_parameter_group_numbers.hpp | 13 +- src/can_hardware_abstraction.hpp | 1 + src/can_hardware_interface_single_thread.cpp | 8 +- src/can_hardware_interface_single_thread.hpp | 1 + src/can_hardware_plugin.hpp | 5 +- src/can_identifier.cpp | 15 - src/can_identifier.hpp | 14 +- src/can_internal_control_function.cpp | 2 +- src/can_internal_control_function.hpp | 2 + src/can_message.cpp | 168 +- src/can_message.hpp | 135 +- src/can_message_data.cpp | 122 + src/can_message_data.hpp | 157 + src/can_network_configuration.cpp | 18 +- src/can_network_configuration.hpp | 26 +- src/can_network_manager.cpp | 269 +- src/can_network_manager.hpp | 74 +- src/can_partnered_control_function.hpp | 1 + src/can_transport_protocol.cpp | 1500 +-- src/can_transport_protocol.hpp | 356 +- src/can_transport_protocol_base.cpp | 106 + src/can_transport_protocol_base.hpp | 133 + src/data_span.hpp | 79 + src/event_dispatcher.hpp | 148 +- src/flex_can_t4_plugin.cpp | 2 +- src/flex_can_t4_plugin.hpp | 4 +- src/isobus_data_dictionary.cpp | 747 ++ src/isobus_data_dictionary.hpp | 45 + src/isobus_device_descriptor_object_pool.cpp | 189 +- src/isobus_device_descriptor_object_pool.hpp | 7 + src/isobus_diagnostic_protocol.cpp | 2 +- src/isobus_diagnostic_protocol.hpp | 5 +- src/isobus_functionalities.hpp | 1 + src/isobus_guidance_interface.cpp | 4 +- src/isobus_guidance_interface.hpp | 5 +- src/isobus_language_command_interface.cpp | 150 +- src/isobus_language_command_interface.hpp | 91 +- src/isobus_maintain_power_interface.hpp | 2 + src/isobus_preferred_addresses.hpp | 225 + src/isobus_shortcut_button_interface.cpp | 2 +- src/isobus_speed_distance_messages.cpp | 8 +- src/isobus_speed_distance_messages.hpp | 4 + src/isobus_task_controller_client.cpp | 126 +- src/isobus_task_controller_client.hpp | 51 +- src/isobus_task_controller_client_objects.cpp | 1 + src/isobus_task_controller_client_objects.hpp | 4 +- src/isobus_virtual_terminal_client.cpp | 2212 ++--- src/isobus_virtual_terminal_client.hpp | 556 +- ..._virtual_terminal_client_state_tracker.cpp | 396 + ..._virtual_terminal_client_state_tracker.hpp | 180 + ..._virtual_terminal_client_update_helper.cpp | 175 + ..._virtual_terminal_client_update_helper.hpp | 89 + src/isobus_virtual_terminal_objects.cpp | 8832 +++++++++++++++++ src/isobus_virtual_terminal_objects.hpp | 4747 ++++++++- src/nmea2000_fast_packet_protocol.cpp | 58 +- src/nmea2000_fast_packet_protocol.hpp | 13 +- src/nmea2000_message_definitions.cpp | 1154 +++ src/nmea2000_message_definitions.hpp | 880 ++ src/nmea2000_message_interface.cpp | 788 ++ src/nmea2000_message_interface.hpp | 339 + src/thread_synchronization.hpp | 45 + 72 files changed, 24026 insertions(+), 3320 deletions(-) create mode 100644 src/can_message_data.cpp create mode 100644 src/can_message_data.hpp create mode 100644 src/can_transport_protocol_base.cpp create mode 100644 src/can_transport_protocol_base.hpp create mode 100644 src/data_span.hpp create mode 100644 src/isobus_data_dictionary.cpp create mode 100644 src/isobus_data_dictionary.hpp create mode 100644 src/isobus_preferred_addresses.hpp create mode 100644 src/isobus_virtual_terminal_client_state_tracker.cpp create mode 100644 src/isobus_virtual_terminal_client_state_tracker.hpp create mode 100644 src/isobus_virtual_terminal_client_update_helper.cpp create mode 100644 src/isobus_virtual_terminal_client_update_helper.hpp create mode 100644 src/isobus_virtual_terminal_objects.cpp create mode 100644 src/nmea2000_message_definitions.cpp create mode 100644 src/nmea2000_message_definitions.hpp create mode 100644 src/nmea2000_message_interface.cpp create mode 100644 src/nmea2000_message_interface.hpp create mode 100644 src/thread_synchronization.hpp diff --git a/examples/VirtualTerminal/VirtualTerminal.ino b/examples/VirtualTerminal/VirtualTerminal.ino index 43f0278..49acd6c 100644 --- a/examples/VirtualTerminal/VirtualTerminal.ino +++ b/examples/VirtualTerminal/VirtualTerminal.ino @@ -8,8 +8,6 @@ auto can0 = std::make_shared(0); std::shared_ptr ISOBUSControlFunction = nullptr; std::shared_ptr ISOBUSDiagnostics = nullptr; std::shared_ptr ExampleVirtualTerminalClient = nullptr; -std::shared_ptr softKeyListener = nullptr; -std::shared_ptr buttonListener = nullptr; // A log sink for the CAN stack class CustomLogger : public CANStackLogger @@ -146,9 +144,9 @@ void setup() { const std::vector vtNameFilters = { filterVirtualTerminal }; auto TestPartnerVT = PartneredControlFunction::create(0, vtNameFilters); ExampleVirtualTerminalClient = std::make_shared(TestPartnerVT, ISOBUSControlFunction); - ExampleVirtualTerminalClient->set_object_pool(0, VirtualTerminalClient::VTVersion::Version3, VT3TestPool, sizeof(VT3TestPool), "AIS1"); - softKeyListener = ExampleVirtualTerminalClient->add_vt_soft_key_event_listener(handleVTKeyEvents); - buttonListener = ExampleVirtualTerminalClient->add_vt_button_event_listener(handleVTKeyEvents); + ExampleVirtualTerminalClient->set_object_pool(0, VT3TestPool, sizeof(VT3TestPool), "AIS1"); + ExampleVirtualTerminalClient->get_vt_button_event_dispatcher().add_listener(handleVTKeyEvents); + ExampleVirtualTerminalClient->get_vt_button_event_dispatcher().add_listener(handleVTKeyEvents); ExampleVirtualTerminalClient->initialize(false); } diff --git a/library.properties b/library.properties index a1ad929..d94ee06 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=AgIsoStack -version=0.1.1 +version=0.1.4 license=MIT author=Adrian Del Grosso maintainer=Adrian Del Grosso diff --git a/src/AgIsoStack.hpp b/src/AgIsoStack.hpp index 3c7abc8..25f560e 100644 --- a/src/AgIsoStack.hpp +++ b/src/AgIsoStack.hpp @@ -1,10 +1,10 @@ /******************************************************************************* ** @file AgIsoStack.hpp ** @author Automatic Code Generation -** @date September 09, 2023 at 11:11:41 +** @date February 08, 2024 at 19:36:28 ** @brief Includes all important files in the AgIsoStack library. ** -** Copyright 2023 The AgIsoStack++ Developers +** Copyright 2024 The AgIsoStack++ Developers *******************************************************************************/ #ifndef AG_ISO_STACK_HPP @@ -23,6 +23,7 @@ #include #include #include +#include #include #include #include @@ -33,29 +34,38 @@ #include #include #include +#include #include +#include #include #include #include #include +#include #include #include #include #include #include #include +#include #include #include #include #include #include #include +#include +#include #include #include #include +#include +#include #include #include #include +#include #include #endif // AG_ISO_STACK_HPP diff --git a/src/can_NAME_filter.cpp b/src/can_NAME_filter.cpp index f0adf8d..3b38f43 100644 --- a/src/can_NAME_filter.cpp +++ b/src/can_NAME_filter.cpp @@ -95,4 +95,4 @@ namespace isobus return retVal; } -} // namespace isobus \ No newline at end of file +} // namespace isobus diff --git a/src/can_NAME_filter.hpp b/src/can_NAME_filter.hpp index 832a612..2858107 100644 --- a/src/can_NAME_filter.hpp +++ b/src/can_NAME_filter.hpp @@ -39,6 +39,7 @@ namespace isobus std::uint32_t get_value() const; /// @brief Returns true if a NAME matches this filter class's components + /// @param[in] nameToCompare A NAME to compare against this filter /// @returns true if a NAME matches this filter class's components bool check_name_matches_filter(const NAME &nameToCompare) const; diff --git a/src/can_address_claim_state_machine.hpp b/src/can_address_claim_state_machine.hpp index 751aee6..959bbad 100644 --- a/src/can_address_claim_state_machine.hpp +++ b/src/can_address_claim_state_machine.hpp @@ -89,13 +89,16 @@ namespace isobus static void process_rx_message(const CANMessage &message, void *parentPointer); /// @brief Sets the current state machine state + /// @param[in] value The state to set the state machine to void set_current_state(State value); /// @brief Sends the PGN request for the address claim PGN + /// @returns true if the message was sent, otherwise false bool send_request_to_claim() const; /// @brief Sends the address claim message /// @param[in] address The address to claim + /// @returns true if the message was sent, otherwise false bool send_address_claim(std::uint8_t address); NAME m_isoname; ///< The ISO NAME to claim as diff --git a/src/can_callbacks.hpp b/src/can_callbacks.hpp index 4a851e5..87fbc1a 100644 --- a/src/can_callbacks.hpp +++ b/src/can_callbacks.hpp @@ -10,6 +10,7 @@ #ifndef CAN_CALLBACKS_HPP #define CAN_CALLBACKS_HPP +#include #include "can_message.hpp" namespace isobus @@ -36,6 +37,14 @@ namespace isobus /// @brief A callback for control functions to get CAN messages using CANLibCallback = void (*)(const CANMessage &message, void *parentPointer); + /// @brief A callback for communicating CAN messages + using CANMessageCallback = std::function; + /// @brief A callback for communicating CAN message frames + using CANMessageFrameCallback = std::function sourceControlFunction, + std::shared_ptr destinationControlFunction, + CANIdentifier::CANPriority priority)>; ///< A callback for sending a CAN frame /// @brief A callback that can inform you when a control function changes state between online and offline using ControlFunctionStateCallback = void (*)(std::shared_ptr controlFunction, ControlFunctionState state); /// @brief A callback to get chunks of data for transfer by a protocol @@ -101,6 +110,7 @@ namespace isobus CANLibCallback get_callback() const; /// @brief Returns the parent pointer for this data object + /// @returns The parent pointer for this data object void *get_parent() const; /// @brief Returns the ICF being used as a filter for this callback diff --git a/src/can_constants.hpp b/src/can_constants.hpp index 561a54e..d1b4772 100644 --- a/src/can_constants.hpp +++ b/src/can_constants.hpp @@ -9,6 +9,8 @@ #ifndef CAN_CONSTANTS_HPP #define CAN_CONSTANTS_HPP +#include + namespace isobus { constexpr std::uint64_t DEFAULT_NAME = 0xFFFFFFFFFFFFFFFF; ///< An invalid NAME used as a default @@ -17,6 +19,7 @@ namespace isobus constexpr std::uint8_t BROADCAST_CAN_ADDRESS = 0xFF; ///< The global/broadcast CAN address constexpr std::uint8_t CAN_DATA_LENGTH = 8; ///< The length of a classical CAN frame constexpr std::uint32_t CAN_PORT_MAXIMUM = 4; ///< An arbitrary limit for memory consumption + constexpr std::uint16_t NULL_OBJECT_ID = 65535; ///< Special ID used to indicate no object } diff --git a/src/can_control_function.hpp b/src/can_control_function.hpp index b741043..aaa2f7f 100644 --- a/src/can_control_function.hpp +++ b/src/can_control_function.hpp @@ -43,6 +43,7 @@ namespace isobus /// @param[in] NAMEValue The NAME of the control function /// @param[in] addressValue The current address of the control function /// @param[in] CANPort The CAN channel index that the control function communicates on + /// @returns A shared pointer to a ControlFunction object created with the parameters passed in static std::shared_ptr create(NAME NAMEValue, std::uint8_t addressValue, std::uint8_t CANPort); /// @brief Destroys this control function, by removing it from the network manager @@ -82,7 +83,7 @@ namespace isobus /// @param[in] type The 'Type' of control function to create ControlFunction(NAME NAMEValue, std::uint8_t addressValue, std::uint8_t CANPort, Type type = Type::External); - friend class CANNetworkManager; + friend class CANNetworkManager; ///< The network manager needs access to the control function's internals #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO static std::mutex controlFunctionProcessingMutex; ///< Protects the control function tables #endif diff --git a/src/can_extended_transport_protocol.cpp b/src/can_extended_transport_protocol.cpp index a594923..b541e7e 100644 --- a/src/can_extended_transport_protocol.cpp +++ b/src/can_extended_transport_protocol.cpp @@ -3,833 +3,917 @@ /// /// @brief A protocol class that handles the ISO11783 extended transport protocol. /// @author Adrian Del Grosso +/// @author Daan Steenbergen /// -/// @copyright 2022 Adrian Del Grosso +/// @copyright 2023 The Open-Agriculture Developers //================================================================================================ #include "can_extended_transport_protocol.hpp" #include "can_general_parameter_group_numbers.hpp" -#include "can_network_configuration.hpp" -#include "can_network_manager.hpp" +#include "can_internal_control_function.hpp" +#include "can_message.hpp" #include "can_stack_logger.hpp" #include "system_timing.hpp" #include "to_string.hpp" #include +#include namespace isobus { - ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::ExtendedTransportProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex) : - sessionMessage(canPortIndex), - sessionDirection(sessionDirection) + ExtendedTransportProtocolManager::StateMachineState ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_state() const { + return state; } - bool ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::operator==(const ExtendedTransportProtocolSession &obj) + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_state(StateMachineState value) { - return ((sessionMessage.get_source_control_function() == obj.sessionMessage.get_source_control_function()) && - (sessionMessage.get_destination_control_function() == obj.sessionMessage.get_destination_control_function()) && - (sessionMessage.get_identifier().get_parameter_group_number() == obj.sessionMessage.get_identifier().get_parameter_group_number())); + state = value; + update_timestamp(); } - std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_message_data_length() const + std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_total_bytes_transferred() const { - if (nullptr != frameChunkCallback) + uint32_t transferred = get_last_packet_number() * PROTOCOL_BYTES_PER_FRAME; + if (transferred > get_message_length()) { - return frameChunkCallbackMessageLength; + transferred = get_message_length(); } - return sessionMessage.get_data_length(); + return transferred; } - ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::~ExtendedTransportProtocolSession() + std::uint8_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_dpo_number_of_packets_remaining() const { + auto packetsSinceDPO = static_cast(get_last_packet_number() - lastAcknowledgedPacketNumber); + return dataPacketOffsetPacketCount - packetsSinceDPO; } - ExtendedTransportProtocolManager::ExtendedTransportProtocolManager() + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_dpo_number_of_packets(std::uint8_t value) { + dataPacketOffsetPacketCount = value; + update_timestamp(); } - ExtendedTransportProtocolManager ::~ExtendedTransportProtocolManager() + std::uint8_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_dpo_number_of_packets() const { - // No need to clean up, as this object is a member of the network manager - // so its callbacks will be cleared at destruction time + return dataPacketOffsetPacketCount; } - void ExtendedTransportProtocolManager::initialize(CANLibBadge) + std::uint8_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_cts_number_of_packet_limit() const { - if (!initialized) + return clearToSendPacketCountLimit; + } + + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_cts_number_of_packet_limit(std::uint8_t value) + { + clearToSendPacketCountLimit = value; + update_timestamp(); + } + + std::uint8_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_last_sequence_number() const + { + return lastSequenceNumber; + } + + std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_last_packet_number() const + { + return lastSequenceNumber + sequenceNumberOffset; + } + + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_sequence_number_offset(std::uint32_t value) + { + sequenceNumberOffset = value; + update_timestamp(); + } + + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_last_sequency_number(std::uint8_t value) + { + lastSequenceNumber = value; + update_timestamp(); + } + + void ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::set_acknowledged_packet_number(std::uint32_t value) + { + lastAcknowledgedPacketNumber = value; + update_timestamp(); + } + + std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_last_acknowledged_packet_number() const + { + return lastAcknowledgedPacketNumber; + } + + std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_number_of_remaining_packets() const + { + return get_total_number_of_packets() - get_last_packet_number(); + } + + std::uint32_t ExtendedTransportProtocolManager::ExtendedTransportProtocolSession::get_total_number_of_packets() const + { + auto totalNumberOfPackets = get_message_length() / PROTOCOL_BYTES_PER_FRAME; + if ((get_message_length() % PROTOCOL_BYTES_PER_FRAME) > 0) { - initialized = true; - CANNetworkManager::CANNetwork.add_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolDataTransfer), process_message, this); - CANNetworkManager::CANNetwork.add_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), process_message, this); + totalNumberOfPackets++; } + return totalNumberOfPackets; } - void ExtendedTransportProtocolManager::process_message(const CANMessage &message) + ExtendedTransportProtocolManager::ExtendedTransportProtocolManager(const CANMessageFrameCallback &sendCANFrameCallback, + const CANMessageCallback &canMessageReceivedCallback, + const CANNetworkConfiguration *configuration) : + sendCANFrameCallback(sendCANFrameCallback), + canMessageReceivedCallback(canMessageReceivedCallback), + configuration(configuration) + { + } + + void ExtendedTransportProtocolManager::process_request_to_send(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint32_t totalMessageSize) { - if ((nullptr != CANNetworkManager::CANNetwork.get_internal_control_function(message.get_destination_control_function()))) + if (activeSessions.size() >= configuration->get_max_number_transport_protocol_sessions()) { - switch (message.get_identifier().get_parameter_group_number()) + // TODO: consider using maximum memory instead of maximum number of sessions + CANStackLogger::warn("[ETP]: Replying with abort to Request To Send (RTS) for 0x%05X, configured maximum number of sessions reached.", parameterGroupNumber); + send_abort(std::static_pointer_cast(destination), source, parameterGroupNumber, ConnectionAbortReason::AlreadyInCMSession); + } + else + { + auto oldSession = get_session(source, destination); + if (nullptr != oldSession) { - case static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement): + if (oldSession->get_parameter_group_number() != parameterGroupNumber) { - if (CAN_DATA_LENGTH == message.get_data_length()) - { - ExtendedTransportProtocolSession *session; - const auto &data = message.get_data(); - const std::uint32_t pgn = (static_cast(data[5]) | (static_cast(data[6]) << 8) | (static_cast(data[7]) << 16)); - - switch (message.get_data()[0]) - { - case EXTENDED_REQUEST_TO_SEND_MULTIPLEXOR: - { - if ((nullptr != message.get_destination_control_function()) && - (activeSessions.size() < CANNetworkManager::CANNetwork.get_configuration().get_max_number_transport_protocol_sessions()) && - (!get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn))) - { - ExtendedTransportProtocolSession *newSession = new ExtendedTransportProtocolSession(ExtendedTransportProtocolSession::Direction::Receive, message.get_can_port_index()); - CANIdentifier tempIdentifierData(CANIdentifier::Type::Extended, pgn, CANIdentifier::CANPriority::PriorityLowest7, message.get_destination_control_function()->get_address(), message.get_source_control_function()->get_address()); - newSession->sessionMessage.set_data_size(static_cast(data[1]) | static_cast(data[2] << 8) | static_cast(data[3] << 16) | static_cast(data[4] << 24)); - newSession->sessionMessage.set_source_control_function(message.get_source_control_function()); - newSession->sessionMessage.set_destination_control_function(message.get_destination_control_function()); - newSession->packetCount = 0xFF; - newSession->sessionMessage.set_identifier(tempIdentifierData); - newSession->state = StateMachineState::ClearToSend; - newSession->timestamp_ms = SystemTiming::get_timestamp_ms(); - activeSessions.push_back(newSession); - } - else if ((get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn)) && - (nullptr != message.get_destination_control_function()) && - (ControlFunction::Type::Internal == message.get_destination_control_function()->get_type())) - { - abort_session(pgn, ConnectionAbortReason::AlreadyInConnectionManagedSessionAndCannotSupportAnother, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " RTS when already in session"); - close_session(session, false); - } - else if ((activeSessions.size() >= CANNetworkManager::CANNetwork.get_configuration().get_max_number_transport_protocol_sessions()) && - (nullptr != message.get_destination_control_function()) && - (ControlFunction::Type::Internal == message.get_destination_control_function()->get_type())) - { - abort_session(pgn, ConnectionAbortReason::SystemResourcesNeededForAnotherTask, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " No Sessions Available"); - close_session(session, false); - } - } - break; - - case EXTENDED_CLEAR_TO_SEND_MULTIPLEXOR: - { - const std::uint8_t packetsToBeSent = data[1]; - - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - if (StateMachineState::WaitForClearToSend == session->state) - { - session->packetCount = packetsToBeSent; - - if (session->packetCount > CANNetworkManager::CANNetwork.get_configuration().get_max_number_of_etp_frames_per_edpo()) - { - session->packetCount = CANNetworkManager::CANNetwork.get_configuration().get_max_number_of_etp_frames_per_edpo(); - } - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - // If 0 was sent as the packet number, they want us to wait. - // Just sit here in this state until we get a non-zero packet count - if (0 != packetsToBeSent) - { - session->lastPacketNumber = 0; - session->state = StateMachineState::TxDataSession; - } - } - else - { - // The session exists, but we're probably already in the TxDataSession state. Need to abort - // In the case of Rx'ing a CTS, we're the source in the session - abort_session(pgn, ConnectionAbortReason::ClearToSendReceivedWhenDataTransferInProgress, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " CTS while in data session"); - close_session(session, false); - } - } - else - { - // We got a CTS but no session exists. Aborting clears up the situation faster than waiting for them to timeout - // In the case of Rx'ing a CTS, we're the source in the session - abort_session(pgn, ConnectionAbortReason::AnyOtherReason, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " CTS With no matching session"); - } - } - break; - - case EXTENDED_DATA_PACKET_OFFSET_MULTIPLEXOR: - { - const std::uint32_t dataPacketOffset = (static_cast(data[2]) | (static_cast(data[3]) << 8) | (static_cast(data[4]) << 16)); - - if (get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn)) - { - const std::uint8_t packetsToBeSent = data[1]; - - if (packetsToBeSent != session->packetCount) - { - if (packetsToBeSent > session->packetCount) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " DPO packet count is greater than CTS"); - abort_session(session, ConnectionAbortReason::EDPONumberOfPacketsGreaterThanClearToSend); - close_session(session, false); - } - else - { - /// @note If byte 2 is less than byte 2 of the ETP.CM_CTS message, then the receiver shall make - /// necessary adjustments to its session to accept the data block defined by the - /// ETP.CM_DPO message and the subsequent ETP.DT packets. - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[ETP]: DPO packet count disagrees with CTS. Using DPO value."); - session->packetCount = packetsToBeSent; - } - } - - if (dataPacketOffset == session->processedPacketsThisSession) - { - // All is good. Proceed with message. - session->lastPacketNumber = 0; - set_state(session, StateMachineState::RxDataSession); - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " DPO packet offset is not valid"); - abort_session(session, ConnectionAbortReason::BadEDPOOffset); - close_session(session, false); - } - } - else - { - bool anySessionMatched = false; - // Do we have any session that matches except for PGN? - for (auto currentSession : activeSessions) - { - if ((currentSession->sessionMessage.get_source_control_function() == message.get_source_control_function()) && - (currentSession->sessionMessage.get_destination_control_function() == message.get_destination_control_function())) - { - // Sending EDPO for this session with mismatched PGN is not allowed - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " EDPO for this session with mismatched PGN is not allowed"); - abort_session(currentSession, ConnectionAbortReason::UnexpectedEDPOPgn); - close_session(session, false); - anySessionMatched = true; - break; - } - } - - if (!anySessionMatched) - { - abort_session(pgn, ConnectionAbortReason::UnexpectedEDPOPacket, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - } - } - } - break; - - case EXTENDED_END_OF_MESSAGE_ACKNOWLEDGEMENT: - { - if ((nullptr != message.get_destination_control_function()) && - (nullptr != message.get_source_control_function())) - { - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - if (StateMachineState::WaitForEndOfMessageAcknowledge == session->state) - { - // We completed our Tx session! - session->state = StateMachineState::None; - close_session(session, true); - } - else - { - abort_session(pgn, ConnectionAbortReason::AnyOtherReason, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - close_session(session, false); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " received EOM in wrong session state"); - } - } - else - { - abort_session(pgn, ConnectionAbortReason::AnyOtherReason, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Sent abort to address " + isobus::to_string(static_cast(message.get_source_control_function()->get_address())) + " EOM without matching session"); - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[ETP]: Bad EOM received, sent to or from an invalid control function"); - } - } - break; - - case EXTENDED_CONNECTION_ABORT_MULTIPLEXOR: - { - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Received an abort for an session with PGN: " + isobus::to_string(pgn)); - close_session(session, false); - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Received an abort with no matching session with PGN: " + isobus::to_string(pgn)); - } - } - break; - - default: - { - } - break; - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[ETP]: Received an invalid ETP CM frame"); - } + CANStackLogger::error("[ETP]: Received Request To Send (RTS) while a session already existed for this source and destination, aborting for 0x%05X...", parameterGroupNumber); + abort_session(oldSession, ConnectionAbortReason::AlreadyInCMSession); } - break; - - case static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolDataTransfer): + else { - ExtendedTransportProtocolSession *tempSession = nullptr; - auto &messageData = message.get_data(); - - if ((CAN_DATA_LENGTH == message.get_data_length()) && - (get_session(tempSession, message.get_source_control_function(), message.get_destination_control_function())) && - (StateMachineState::RxDataSession == tempSession->state) && - (messageData[SEQUENCE_NUMBER_DATA_INDEX] == (tempSession->lastPacketNumber + 1))) - { - for (std::uint8_t i = SEQUENCE_NUMBER_DATA_INDEX; (i < PROTOCOL_BYTES_PER_FRAME) && (((PROTOCOL_BYTES_PER_FRAME * tempSession->processedPacketsThisSession) + i) < tempSession->get_message_data_length()); i++) - { - std::uint32_t currentDataIndex = (PROTOCOL_BYTES_PER_FRAME * tempSession->processedPacketsThisSession) + i; - tempSession->sessionMessage.set_data(messageData[1 + SEQUENCE_NUMBER_DATA_INDEX + i], currentDataIndex); - } - tempSession->lastPacketNumber++; - tempSession->processedPacketsThisSession++; - if ((tempSession->processedPacketsThisSession * PROTOCOL_BYTES_PER_FRAME) >= tempSession->get_message_data_length()) - { - if (nullptr != tempSession->sessionMessage.get_destination_control_function()) - { - send_end_of_session_acknowledgement(tempSession); - } - CANNetworkManager::CANNetwork.process_any_control_function_pgn_callbacks(tempSession->sessionMessage); - CANNetworkManager::CANNetwork.protocol_message_callback(tempSession->sessionMessage); - close_session(tempSession, true); - } - tempSession->timestamp_ms = SystemTiming::get_timestamp_ms(); - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[ETP]: Received an unexpected or invalid data transfer frame"); - } + CANStackLogger::warn("[ETP]: Received Request To Send (RTS) while a session already existed for this source and destination and parameterGroupNumber, overwriting for 0x%05X...", parameterGroupNumber); + close_session(oldSession, false); } - break; } + + auto newSession = std::make_shared(ExtendedTransportProtocolSession::Direction::Receive, + std::unique_ptr(new CANMessageDataVector(totalMessageSize)), + parameterGroupNumber, + totalMessageSize, + source, + destination, + nullptr, // No callback + nullptr); + + // Request the maximum number of packets per DPO via the CTS message + newSession->set_cts_number_of_packet_limit(configuration->get_number_of_packets_per_dpo_message()); + + newSession->set_state(StateMachineState::SendClearToSend); + activeSessions.push_back(newSession); + CANStackLogger::debug("[ETP]: New rx session for 0x%05X. Source: %hu, destination: %hu", parameterGroupNumber, source->get_address(), destination->get_address()); + update_state_machine(newSession); } } - void ExtendedTransportProtocolManager::process_message(const CANMessage &message, void *parent) + void ExtendedTransportProtocolManager::process_clear_to_send(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint8_t packetsToBeSent, + std::uint32_t nextPacketNumber) { - if (nullptr != parent) + auto session = get_session(destination, source); + if (nullptr != session) + { + if (session->get_parameter_group_number() != parameterGroupNumber) + { + CANStackLogger::error("[ETP]: Received a Clear To Send (CTS) message for 0x%05X while a session already existed for this source and destination, sending abort for both...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + send_abort(std::static_pointer_cast(destination), source, parameterGroupNumber, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + } + else if (nextPacketNumber > session->get_total_number_of_packets()) + { + CANStackLogger::error("[ETP]: Received a Clear To Send (CTS) message for 0x%05X with a bad sequence number, aborting...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::NumberOfClearToSendPacketsExceedsMessage); + } + else if (StateMachineState::WaitForClearToSend != session->state) + { + // The session exists, but we're not in the right state to receive a CTS, so we must abort + CANStackLogger::warn("[ETP]: Received a Clear To Send (CTS) message for 0x%05X, but not expecting one, aborting session->", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + } + else + { + session->set_acknowledged_packet_number(nextPacketNumber - 1); + session->set_cts_number_of_packet_limit(packetsToBeSent); + + // If 0 was sent as the packet number, they want us to wait. + // Just sit here in this state until we get a non-zero packet count + if (0 != packetsToBeSent) + { + session->set_state(StateMachineState::SendDataPacketOffset); + } + } + } + else { - reinterpret_cast(parent)->process_message(message); + // We got a CTS but no session exists, by the standard we must ignore it + CANStackLogger::warn("[ETP]: Received Clear To Send (CTS) for 0x%05X while no session existed for this source and destination, ignoring...", parameterGroupNumber); } } - bool ExtendedTransportProtocolManager::protocol_transmit_message(std::uint32_t parameterGroupNumber, - const std::uint8_t *dataBuffer, - std::uint32_t messageLength, - std::shared_ptr source, - std::shared_ptr destination, - TransmitCompleteCallback sessionCompleteCallback, - void *parentPointer, - DataChunkCallback frameChunkCallback) + void ExtendedTransportProtocolManager::process_data_packet_offset(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint8_t numberOfPackets, + std::uint32_t packetOffset) { - ExtendedTransportProtocolSession *session; - bool retVal = false; - - if ((messageLength < MAX_PROTOCOL_DATA_LENGTH) && - (messageLength >= MIN_PROTOCOL_DATA_LENGTH) && - (nullptr != destination) && - ((nullptr != dataBuffer) || - (nullptr != frameChunkCallback)) && - (nullptr != source) && - (true == source->get_address_valid()) && - (destination->get_address_valid()) && - (!get_session(session, source, destination, parameterGroupNumber))) + auto session = get_session(source, destination); + if (nullptr != session) { - ExtendedTransportProtocolSession *newSession = new ExtendedTransportProtocolSession(ExtendedTransportProtocolSession::Direction::Transmit, - source->get_can_port()); - - if (dataBuffer != nullptr) + if (session->get_parameter_group_number() != parameterGroupNumber) { - newSession->sessionMessage.set_data(dataBuffer, messageLength); + CANStackLogger::error("[ETP]: Received a Data Packet Offset message for 0x%05X while a session already existed for this source and destination with a different PGN, sending abort for both...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::UnexpectedDataPacketOffsetPGN); + send_abort(std::static_pointer_cast(destination), source, parameterGroupNumber, ConnectionAbortReason::UnexpectedDataPacketOffsetPGN); } - else + else if (StateMachineState::WaitForDataPacketOffset != session->state) { - newSession->frameChunkCallback = frameChunkCallback; - newSession->frameChunkCallbackMessageLength = messageLength; + // The session exists, but we're not in the right state to receive a DPO, so we must abort + CANStackLogger::warn("[ETP]: Received a Data Packet Offset message for 0x%05X, but not expecting one, aborting session->", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::UnexpectedDataPacketOffsetReceived); } - newSession->sessionMessage.set_source_control_function(source); - newSession->sessionMessage.set_destination_control_function(destination); - newSession->packetCount = (messageLength / PROTOCOL_BYTES_PER_FRAME); - newSession->lastPacketNumber = 0; - newSession->processedPacketsThisSession = 0; - newSession->sessionCompleteCallback = sessionCompleteCallback; - newSession->parent = parentPointer; - if (0 != (messageLength % PROTOCOL_BYTES_PER_FRAME)) + else if (numberOfPackets > session->get_cts_number_of_packet_limit()) { - newSession->packetCount++; + CANStackLogger::error("[ETP]: Received a Data Packet Offset message for 0x%05X with an higher number of packets than our CTS, aborting...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::DataPacketOffsetExceedsClearToSend); } - CANIdentifier messageVirtualID(CANIdentifier::Type::Extended, - parameterGroupNumber, - CANIdentifier::CANPriority::PriorityDefault6, - destination->get_address(), - source->get_address()); + else if (packetOffset != session->get_last_acknowledged_packet_number()) + { + CANStackLogger::error("[ETP]: Received a Data Packet Offset message for 0x%05X with a bad sequence number, aborting...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::BadDataPacketOffset); + } + else + { + session->set_dpo_number_of_packets(numberOfPackets); + session->set_sequence_number_offset(packetOffset); + session->set_last_sequency_number(0); - newSession->sessionMessage.set_identifier(messageVirtualID); - set_state(newSession, StateMachineState::RequestToSend); - activeSessions.push_back(newSession); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[ETP]: New ETP Session. Dest: " + isobus::to_string(static_cast(destination->get_address()))); - retVal = true; + // If 0 was sent as the packet number, they want us to wait. + // Just sit here in this state until we get a non-zero packet count + if (0 != numberOfPackets) + { + session->set_state(StateMachineState::WaitForDataTransferPacket); + } + } } - return retVal; - } - - void ExtendedTransportProtocolManager::update(CANLibBadge) - { - for (auto i : activeSessions) + else { - update_state_machine(i); + // We got a CTS but no session exists, by the standard we must ignore it + CANStackLogger::warn("[ETP]: Received Data Packet Offset for 0x%05X while no session existed for this source and destination, ignoring...", parameterGroupNumber); } } - bool ExtendedTransportProtocolManager::abort_session(ExtendedTransportProtocolSession *session, ConnectionAbortReason reason) + void ExtendedTransportProtocolManager::process_end_of_session_acknowledgement(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint32_t numberOfBytesTransferred) { - bool retVal = false; - + auto session = get_session(destination, source); if (nullptr != session) { - std::shared_ptr myControlFunction; - std::shared_ptr partnerControlFunction; - std::array data; - std::uint32_t pgn = session->sessionMessage.get_identifier().get_parameter_group_number(); - - if (ExtendedTransportProtocolSession::Direction::Transmit == session->sessionDirection) + if (StateMachineState::WaitForEndOfMessageAcknowledge == session->state) { - myControlFunction = CANNetworkManager::CANNetwork.get_internal_control_function(session->sessionMessage.get_source_control_function()); - partnerControlFunction = session->sessionMessage.get_destination_control_function(); + session->state = StateMachineState::None; + bool successful = (numberOfBytesTransferred == session->get_message_length()); + close_session(session, successful); + CANStackLogger::debug("[ETP]: Completed tx session for 0x%05X from %hu", parameterGroupNumber, source->get_address()); } else { - myControlFunction = CANNetworkManager::CANNetwork.get_internal_control_function(session->sessionMessage.get_destination_control_function()); - partnerControlFunction = session->sessionMessage.get_source_control_function(); - } - - data[0] = EXTENDED_CONNECTION_ABORT_MULTIPLEXOR; - data[1] = static_cast(reason); - data[2] = 0xFF; - data[3] = 0xFF; - data[4] = 0xFF; - data[5] = static_cast(pgn & 0xFF); - data[6] = static_cast((pgn >> 8) & 0xFF); - data[7] = static_cast((pgn >> 16) & 0xFF); - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - data.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::CANPriority::PriorityLowest7); + // The session exists, but we're not in the right state to receive an EOM, by the standard we must ignore it + CANStackLogger::warn("[ETP]: Received an End Of Message Acknowledgement message for 0x%05X, but not expecting one, ignoring.", parameterGroupNumber); + } + } + else + { + CANStackLogger::warn("[ETP]: Received End Of Message Acknowledgement for 0x%05X while no session existed for this source and destination, ignoring.", parameterGroupNumber); } - return retVal; } - bool ExtendedTransportProtocolManager::abort_session(std::uint32_t parameterGroupNumber, ConnectionAbortReason reason, std::shared_ptr source, std::shared_ptr destination) + void ExtendedTransportProtocolManager::process_abort(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + ExtendedTransportProtocolManager::ConnectionAbortReason reason) { - std::array data; + bool foundSession = false; + + auto session = get_session(source, destination); + if ((nullptr != session) && (session->get_parameter_group_number() == parameterGroupNumber)) + { + foundSession = true; + CANStackLogger::error("[ETP]: Received an abort (reason=%hu) for an rx session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); + close_session(session, false); + } + session = get_session(destination, source); + if ((nullptr != session) && (session->get_parameter_group_number() == parameterGroupNumber)) + { + foundSession = true; + CANStackLogger::error("[ETP]: Received an abort (reason=%hu) for a tx session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); + close_session(session, false); + } - data[0] = EXTENDED_CONNECTION_ABORT_MULTIPLEXOR; - data[1] = static_cast(reason); - data[2] = 0xFF; - data[3] = 0xFF; - data[4] = 0xFF; - data[5] = static_cast(parameterGroupNumber & 0xFF); - data[6] = static_cast((parameterGroupNumber >> 8) & 0xFF); - data[7] = static_cast((parameterGroupNumber >> 16) & 0xFF); - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - data.data(), - CAN_DATA_LENGTH, - source, - destination, - CANIdentifier::CANPriority::PriorityLowest7); + if (!foundSession) + { + CANStackLogger::warn("[ETP]: Received an abort (reason=%hu) with no matching session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); + } } - void ExtendedTransportProtocolManager::close_session(ExtendedTransportProtocolSession *session, bool successfull) + void ExtendedTransportProtocolManager::process_connection_management_message(const CANMessage &message) { - if (nullptr != session) + if (CAN_DATA_LENGTH != message.get_data_length()) + { + CANStackLogger::warn("[ETP]: Received a Connection Management message of invalid length %hu", message.get_data_length()); + return; + } + + const auto parameterGroupNumber = message.get_uint24_at(5); + + switch (message.get_uint8_at(0)) { - process_session_complete_callback(session, successfull); - auto sessionLocation = std::find(activeSessions.begin(), activeSessions.end(), session); - if (activeSessions.end() != sessionLocation) + case REQUEST_TO_SEND_MULTIPLEXOR: + { + const auto totalMessageSize = message.get_uint32_at(1); + process_request_to_send(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + totalMessageSize); + } + break; + + case CLEAR_TO_SEND_MULTIPLEXOR: + { + const auto packetsToBeSent = message.get_uint8_at(1); + const auto nextPacketNumber = message.get_uint24_at(2); + process_clear_to_send(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + packetsToBeSent, + nextPacketNumber); + } + break; + + case DATA_PACKET_OFFSET_MULTIPLXOR: + { + const auto numberOfPackets = message.get_uint8_at(1); + const auto packetOffset = message.get_uint24_at(2); + process_data_packet_offset(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + numberOfPackets, + packetOffset); + } + break; + + case END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR: + { + const auto numberOfBytesTransferred = message.get_uint32_at(1); + process_end_of_session_acknowledgement(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + numberOfBytesTransferred); + } + break; + + case CONNECTION_ABORT_MULTIPLEXOR: { - activeSessions.erase(sessionLocation); - delete session; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[ETP]: Session Closed"); + const auto reason = static_cast(message.get_uint8_at(1)); + process_abort(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + reason); } + break; + + default: + { + CANStackLogger::warn("[ETP]: Bad Mux in Transport Protocol Connection Management message"); + } + break; } } - bool ExtendedTransportProtocolManager::get_session(ExtendedTransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination) const + void ExtendedTransportProtocolManager::process_data_transfer_message(const CANMessage &message) { - session = nullptr; + if (CAN_DATA_LENGTH != message.get_data_length()) + { + CANStackLogger::warn("[ETP]: Received a Data Transfer message of invalid length %hu", message.get_data_length()); + return; + } - for (auto i : activeSessions) + auto source = message.get_source_control_function(); + auto destination = message.get_destination_control_function(); + + auto sequenceNumber = message.get_uint8_at(SEQUENCE_NUMBER_DATA_INDEX); + + auto session = get_session(source, destination); + if (nullptr != session) { - if ((i->sessionMessage.get_source_control_function() == source) && - (i->sessionMessage.get_destination_control_function() == destination)) + if (StateMachineState::WaitForDataTransferPacket != session->state) { - session = i; - break; + CANStackLogger::warn("[ETP]: Received a Data Transfer message from %hu while not expecting one, sending abort", source->get_address()); + abort_session(session, ConnectionAbortReason::UnexpectedDataTransferPacketReceived); + } + else if (sequenceNumber == session->get_last_sequence_number()) + { + CANStackLogger::error("[ETP]: Aborting rx session for 0x%05X due to duplicate sequence number", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::DuplicateSequenceNumber); + } + else if (sequenceNumber == (session->get_last_sequence_number() + 1)) + { + // Convert data type to a vector to allow for manipulation + auto &data = static_cast(session->get_data()); + + // Correct sequence number, copy the data + for (std::uint8_t i = 0; i < PROTOCOL_BYTES_PER_FRAME; i++) + { + std::uint32_t currentDataIndex = (PROTOCOL_BYTES_PER_FRAME * session->get_last_packet_number()) + i; + if (currentDataIndex < session->get_message_length()) + { + data.set_byte(currentDataIndex, message.get_uint8_at(1 + i)); + } + else + { + // Reached the end of the message, no need to copy any more data + break; + } + } + + session->set_last_sequency_number(sequenceNumber); + if (session->get_number_of_remaining_packets() == 0) + { + // Send End of Message Acknowledgement for sessions with specific destination only + send_end_of_session_acknowledgement(session); + + // Construct the completed message + CANIdentifier identifier(CANIdentifier::Type::Extended, + session->get_parameter_group_number(), + CANIdentifier::CANPriority::PriorityDefault6, + destination->get_address(), + source->get_address()); + CANMessage completedMessage(CANMessage::Type::Receive, + identifier, + std::move(data), + source, + destination, + 0); + + canMessageReceivedCallback(completedMessage); + close_session(session, true); + CANStackLogger::debug("[ETP]: Completed rx session for 0x%05X from %hu", session->get_parameter_group_number(), source->get_address()); + } + else if (session->get_dpo_number_of_packets_remaining() == 0) + { + session->set_state(StateMachineState::SendClearToSend); + update_state_machine(session); + } + } + else + { + CANStackLogger::error("[ETP]: Aborting rx session for 0x%05X due to bad sequence number", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::BadSequenceNumber); } } - return (nullptr != session); } - bool ExtendedTransportProtocolManager::get_session(ExtendedTransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination, std::uint32_t parameterGroupNumber) const + void ExtendedTransportProtocolManager::process_message(const CANMessage &message) { - bool retVal = false; - session = nullptr; - - if ((get_session(session, source, destination)) && - (session->sessionMessage.get_identifier().get_parameter_group_number() == parameterGroupNumber)) + // TODO: Allow sniffing of messages to all addresses, not just the ones we normally listen to (#297) + if (message.has_valid_source_control_function() && message.is_destination_our_device()) { - retVal = true; + switch (message.get_identifier().get_parameter_group_number()) + { + case static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement): + { + process_connection_management_message(message); + } + break; + + case static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolDataTransfer): + { + process_data_transfer_message(message); + } + break; + + default: + break; + } } - return retVal; } - void ExtendedTransportProtocolManager::process_session_complete_callback(ExtendedTransportProtocolSession *session, bool success) + bool ExtendedTransportProtocolManager::protocol_transmit_message(std::uint32_t parameterGroupNumber, + std::unique_ptr &data, + std::shared_ptr source, + std::shared_ptr destination, + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer) { - if ((nullptr != session) && - (nullptr != session->sessionCompleteCallback) && - (nullptr != session->sessionMessage.get_source_control_function()) && - (ControlFunction::Type::Internal == session->sessionMessage.get_source_control_function()->get_type())) + // Return false early if we can't send the message + if ((nullptr == data) || (data->size() <= 1785) || (data->size() > MAX_PROTOCOL_DATA_LENGTH)) { - session->sessionCompleteCallback(session->sessionMessage.get_identifier().get_parameter_group_number(), - session->get_message_data_length(), - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - success, - session->parent); + // Invalid message length + return false; } + else if ((nullptr == source) || (!source->get_address_valid()) || + (nullptr == destination) || (!destination->get_address_valid()) || + has_session(source, destination)) + { + // Invalid source/destination or already have a session for this source and destination + return false; + } + + // We can handle this message! If we only have a view of the data, let's clone the data, + // so we don't have to worry about it being deleted. + data = data->copy_if_not_owned(std::move(data)); + auto dataLength = static_cast(data->size()); + + auto session = std::make_shared(ExtendedTransportProtocolSession::Direction::Transmit, + std::move(data), + parameterGroupNumber, + dataLength, + source, + destination, + sessionCompleteCallback, + parentPointer); + session->set_state(StateMachineState::SendRequestToSend); + CANStackLogger::debug("[ETP]: New tx session for 0x%05X. Source: %hu, destination: %hu", + parameterGroupNumber, + source->get_address(), + destination->get_address()); + + activeSessions.push_back(session); + update_state_machine(session); + return true; } - bool ExtendedTransportProtocolManager::send_end_of_session_acknowledgement(ExtendedTransportProtocolSession *session) const + void ExtendedTransportProtocolManager::update() { - bool retVal = false; - - if (nullptr != session) + // We use a fancy for loop here to allow us to remove sessions from the list while iterating + for (std::size_t i = activeSessions.size(); i > 0; i--) { - std::uint32_t totalBytesTransferred = (session->get_message_data_length()); - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { EXTENDED_END_OF_MESSAGE_ACKNOWLEDGEMENT, - static_cast(totalBytesTransferred & 0xFF), - static_cast((totalBytesTransferred >> 8) & 0xFF), - static_cast((totalBytesTransferred >> 16) & 0xFF), - static_cast((totalBytesTransferred >> 24) & 0xFF), - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_destination_control_function()), - session->sessionMessage.get_source_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + auto session = activeSessions.at(i - 1); + if (!session->get_source()->get_address_valid()) + { + CANStackLogger::warn("[ETP]: Closing active session as the source control function is no longer valid"); + close_session(session, false); + } + else if (!session->get_destination()->get_address_valid()) + { + CANStackLogger::warn("[ETP]: Closing active session as the destination control function is no longer valid"); + close_session(session, false); + } + else if (StateMachineState::None != session->state) + { + update_state_machine(session); + } } - return retVal; } - bool ExtendedTransportProtocolManager::send_extended_connection_mode_clear_to_send(ExtendedTransportProtocolSession *session) const + void ExtendedTransportProtocolManager::send_data_transfer_packets(std::shared_ptr &session) const { - bool retVal = false; + std::array buffer; + std::uint8_t framesToSend = session->get_dpo_number_of_packets_remaining(); + if (framesToSend > configuration->get_max_number_of_network_manager_protocol_frames_per_update()) + { + framesToSend = configuration->get_max_number_of_network_manager_protocol_frames_per_update(); + } - if (nullptr != session) + // Try and send packets + for (std::uint8_t i = 0; i < framesToSend; i++) { - std::uint32_t packetMax = ((((session->get_message_data_length() - 1) / 7) + 1) - session->processedPacketsThisSession); + buffer[0] = session->get_last_sequence_number() + 1; - if (packetMax > 0xFF) + std::uint32_t dataOffset = session->get_last_packet_number() * PROTOCOL_BYTES_PER_FRAME; + for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) { - packetMax = 0xFF; + std::uint32_t index = dataOffset + j; + if (index < session->get_message_length()) + { + buffer[1 + j] = session->get_data().get_byte(index); + } + else + { + buffer[1 + j] = 0xFF; + } } - if (packetMax < session->packetCount) + if (sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolDataTransfer), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + session->get_destination(), + CANIdentifier::CANPriority::PriorityLowest7)) { - session->packetCount = packetMax; // If we're sending a CTS with less than 0xFF, set the expected packet count to the CTS packet count + session->set_last_sequency_number(session->get_last_sequence_number() + 1); + } + else + { + // Process more next time protocol is updated + break; } - - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { EXTENDED_CLEAR_TO_SEND_MULTIPLEXOR, - static_cast(packetMax), /// @todo Make CTS Max user configurable - static_cast((session->processedPacketsThisSession + 1) & 0xFF), - static_cast(((session->processedPacketsThisSession + 1) >> 8) & 0xFF), - static_cast(((session->processedPacketsThisSession + 1) >> 16) & 0xFF), - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_destination_control_function()), - session->sessionMessage.get_source_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); } - return retVal; - } - bool ExtendedTransportProtocolManager::send_extended_connection_mode_request_to_send(const ExtendedTransportProtocolSession *session) const - { - bool retVal = false; - - if (nullptr != session) + if (session->get_number_of_remaining_packets() == 0) { - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { EXTENDED_REQUEST_TO_SEND_MULTIPLEXOR, - static_cast(session->get_message_data_length() & 0xFF), - static_cast((session->get_message_data_length() >> 8) & 0xFF), - static_cast((session->get_message_data_length() >> 16) & 0xFF), - static_cast((session->get_message_data_length() >> 24) & 0xFF), - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + session->set_state(StateMachineState::WaitForEndOfMessageAcknowledge); } - return retVal; - } - - bool ExtendedTransportProtocolManager::send_extended_connection_mode_data_packet_offset(const ExtendedTransportProtocolSession *session) const - { - bool retVal = false; - - if (nullptr != session) + else if (session->get_dpo_number_of_packets_remaining() == 0) { - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { EXTENDED_DATA_PACKET_OFFSET_MULTIPLEXOR, - static_cast(session->packetCount & 0xFF), - static_cast((session->processedPacketsThisSession) & 0xFF), - static_cast((session->processedPacketsThisSession >> 8) & 0xFF), - static_cast((session->processedPacketsThisSession >> 16) & 0xFF), - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + session->set_state(StateMachineState::WaitForClearToSend); } - return retVal; } - void ExtendedTransportProtocolManager::set_state(ExtendedTransportProtocolSession *session, StateMachineState value) + void ExtendedTransportProtocolManager::update_state_machine(std::shared_ptr &session) { - if (nullptr != session) + switch (session->state) { - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - session->state = value; - } - } + case StateMachineState::None: + break; - void ExtendedTransportProtocolManager::update_state_machine(ExtendedTransportProtocolSession *session) - { - if (nullptr != session) - { - switch (session->state) + case StateMachineState::SendRequestToSend: + { + if (send_request_to_send(session)) + { + session->set_state(StateMachineState::WaitForClearToSend); + } + } + break; + + case StateMachineState::WaitForClearToSend: { - case StateMachineState::RequestToSend: + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) { - if (send_extended_connection_mode_request_to_send(session)) + CANStackLogger::error("[ETP]: Timeout tx session for 0x%05X (expected CTS)", session->get_parameter_group_number()); + if (session->get_cts_number_of_packet_limit() > 0) { - set_state(session, StateMachineState::WaitForClearToSend); + // A connection is only considered established if we've received at least one CTS before + // And we can only abort a connection if it's considered established + abort_session(session, ConnectionAbortReason::Timeout); } else { - if (SystemTiming::time_expired_ms(session->timestamp_ms, T2_3_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Aborting session, T2-3 timeout reached while in RTS state"); - abort_session(session, ConnectionAbortReason::Timeout); - close_session(session, false); - } + close_session(session, false); } } - break; + } + break; - case StateMachineState::WaitForEndOfMessageAcknowledge: - case StateMachineState::WaitForExtendedDataPacketOffset: - case StateMachineState::WaitForClearToSend: + case StateMachineState::SendClearToSend: + { + if (send_clear_to_send(session)) { - if (SystemTiming::time_expired_ms(session->timestamp_ms, T2_3_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Aborting session, T2-3 timeout reached while waiting for CTS"); - abort_session(session, ConnectionAbortReason::Timeout); - close_session(session, false); - } + session->set_state(StateMachineState::WaitForDataPacketOffset); } - break; + } + break; - case StateMachineState::TxDataSession: + case StateMachineState::WaitForDataPacketOffset: + { + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) { - if (nullptr != session->sessionMessage.get_destination_control_function()) - { - std::uint8_t dataBuffer[CAN_DATA_LENGTH]; - bool proceedToSendDataPackets = true; - bool sessionStillValid = true; - - if (0 == session->lastPacketNumber) - { - proceedToSendDataPackets = send_extended_connection_mode_data_packet_offset(session); - } - - if (proceedToSendDataPackets) - { - std::uint32_t framesSentThisUpdate = 0; - // Try and send packets - for (std::uint32_t i = session->lastPacketNumber; i < session->packetCount; i++) - { - dataBuffer[0] = (session->lastPacketNumber + 1); - - if (nullptr != session->frameChunkCallback) - { - // Use the callback to get this frame's data - std::uint8_t callbackBuffer[7] = { - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF - }; - std::uint32_t numberBytesLeft = (session->get_message_data_length() - (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)); - - if (numberBytesLeft > PROTOCOL_BYTES_PER_FRAME) - { - numberBytesLeft = PROTOCOL_BYTES_PER_FRAME; - } - - bool callbackSuccessful = session->frameChunkCallback(dataBuffer[0], (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession), numberBytesLeft, callbackBuffer, session->parent); - - if (callbackSuccessful) - { - for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) - { - dataBuffer[1 + j] = callbackBuffer[j]; - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Aborting session, unable to transfer chunk of data (numberBytesLeft=" + to_string(numberBytesLeft) + ")"); - abort_session(session, ConnectionAbortReason::AnyOtherReason); - close_session(session, false); - sessionStillValid = false; - break; - } - } - else - { - // Use the data buffer to get the data for this frame - for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) - { - std::uint32_t index = (j + (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)); - if (index < session->get_message_data_length()) - { - dataBuffer[1 + j] = session->sessionMessage.get_data()[j + (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)]; - } - else - { - dataBuffer[1 + j] = 0xFF; - } - } - } - - if (CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolDataTransfer), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - CANIdentifier::CANPriority::PriorityLowest7)) - { - framesSentThisUpdate++; - session->lastPacketNumber++; - session->processedPacketsThisSession++; - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - - if (framesSentThisUpdate >= CANNetworkManager::CANNetwork.get_configuration().get_max_number_of_network_manager_protocol_frames_per_update()) - { - break; // Throttle the session - } - } - else - { - // Process more next time protocol is updated - break; - } - } - } - - if (sessionStillValid) - { - if ((session->lastPacketNumber == (session->packetCount)) && - (session->get_message_data_length() <= (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession))) - { - set_state(session, StateMachineState::WaitForEndOfMessageAcknowledge); - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - } - else if (session->lastPacketNumber == session->packetCount) - { - set_state(session, StateMachineState::WaitForClearToSend); - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - } - } - } + CANStackLogger::error("[ETP]: Timeout rx session for 0x%05X (expected DPO)", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::Timeout); } - break; + } + break; - case StateMachineState::RxDataSession: + case StateMachineState::SendDataPacketOffset: + { + if (send_data_packet_offset(session)) { - if (session->packetCount == session->lastPacketNumber) - { - set_state(session, StateMachineState::ClearToSend); - } - else if (SystemTiming::time_expired_ms(session->timestamp_ms, T1_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Aborting session, RX T1 timeout reached"); - abort_session(session, ConnectionAbortReason::Timeout); - close_session(session, false); - } + session->set_state(StateMachineState::SendDataTransferPackets); } - break; + } + break; + + case StateMachineState::SendDataTransferPackets: + { + send_data_transfer_packets(session); + } + break; - case StateMachineState::ClearToSend: + case StateMachineState::WaitForDataTransferPacket: + { + if (session->get_time_since_last_update() > T1_TIMEOUT_MS) { - if (send_extended_connection_mode_clear_to_send(session)) - { - set_state(session, StateMachineState::WaitForExtendedDataPacketOffset); - } - else if (SystemTiming::time_expired_ms(session->timestamp_ms, T2_3_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[ETP]: Aborting session, T2-3 timeout reached while in CTS state"); - abort_session(session, ConnectionAbortReason::Timeout); - close_session(session, false); - } + CANStackLogger::error("[ETP]: Timeout for destination-specific rx session (expected sequential data frame)"); + abort_session(session, ConnectionAbortReason::Timeout); } - break; + } + break; - default: + case StateMachineState::WaitForEndOfMessageAcknowledge: + { + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) { - // Nothing to do. + CANStackLogger::error("[ETP]: Timeout tx session for 0x%05X (expected EOMA)", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::Timeout); } - break; } + break; + } + } + + bool ExtendedTransportProtocolManager::abort_session(std::shared_ptr &session, ConnectionAbortReason reason) + { + bool retVal = false; + std::shared_ptr myControlFunction; + std::shared_ptr partnerControlFunction; + if (ExtendedTransportProtocolSession::Direction::Transmit == session->get_direction()) + { + myControlFunction = std::static_pointer_cast(session->get_source()); + partnerControlFunction = session->get_destination(); + } + else + { + myControlFunction = std::static_pointer_cast(session->get_destination()); + partnerControlFunction = session->get_source(); + } + + if ((nullptr != myControlFunction) && (nullptr != partnerControlFunction)) + { + retVal = send_abort(myControlFunction, partnerControlFunction, session->get_parameter_group_number(), reason); + } + close_session(session, false); + return retVal; + } + + bool ExtendedTransportProtocolManager::send_abort(std::shared_ptr sender, + std::shared_ptr receiver, + std::uint32_t parameterGroupNumber, + ConnectionAbortReason reason) const + { + const std::array buffer{ + CONNECTION_ABORT_MULTIPLEXOR, + static_cast(reason), + 0xFF, + 0xFF, + 0xFF, + static_cast(parameterGroupNumber & 0xFF), + static_cast((parameterGroupNumber >> 8) & 0xFF), + static_cast((parameterGroupNumber >> 16) & 0xFF) + }; + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + sender, + receiver, + CANIdentifier::CANPriority::PriorityLowest7); + } + + void ExtendedTransportProtocolManager::close_session(std::shared_ptr &session, bool successful) + { + session->complete(successful); + auto sessionLocation = std::find(activeSessions.begin(), activeSessions.end(), session); + if (activeSessions.end() != sessionLocation) + { + activeSessions.erase(sessionLocation); + CANStackLogger::debug("[ETP]: Session Closed"); + } + } + + bool ExtendedTransportProtocolManager::send_request_to_send(std::shared_ptr &session) const + { + const std::array buffer{ + REQUEST_TO_SEND_MULTIPLEXOR, + static_cast(session->get_message_length() & 0xFF), + static_cast((session->get_message_length() >> 8) & 0xFF), + static_cast((session->get_message_length() >> 16) & 0xFF), + static_cast((session->get_message_length() >> 24) & 0xFF), + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + session->get_destination(), + CANIdentifier::CANPriority::PriorityLowest7); + } + + bool ExtendedTransportProtocolManager::send_clear_to_send(std::shared_ptr &session) const + { + std::uint32_t nextPacketNumber = session->get_last_packet_number() + 1; + std::uint8_t packetLimit = session->get_cts_number_of_packet_limit(); + + if (packetLimit > session->get_number_of_remaining_packets()) + { + packetLimit = static_cast(session->get_number_of_remaining_packets()); + } + + const std::array buffer{ + CLEAR_TO_SEND_MULTIPLEXOR, + packetLimit, + static_cast(nextPacketNumber & 0xFF), + static_cast((nextPacketNumber >> 8) & 0xFF), + static_cast((nextPacketNumber >> 16) & 0xFF), + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + bool retVal = sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_destination()), // Since we're the receiving side, we are the destination of the session + session->get_source(), + CANIdentifier::CANPriority::PriorityLowest7); + if (retVal) + { + session->set_acknowledged_packet_number(session->get_last_packet_number()); + } + return retVal; + } + + bool isobus::ExtendedTransportProtocolManager::send_data_packet_offset(std::shared_ptr &session) const + { + std::uint8_t packetsThisSegment = 0xFF; + if (packetsThisSegment > session->get_number_of_remaining_packets()) + { + packetsThisSegment = static_cast(session->get_number_of_remaining_packets()); } + + if (packetsThisSegment > session->get_cts_number_of_packet_limit()) + { + packetsThisSegment = session->get_cts_number_of_packet_limit(); + } + if (packetsThisSegment > configuration->get_number_of_packets_per_dpo_message()) + { + CANStackLogger::debug("[TP]: Received Request To Send (RTS) with a CTS packet count of %hu, which is greater than the configured maximum of %hu, using the configured maximum instead.", packetsThisSegment, configuration->get_number_of_packets_per_dpo_message()); + packetsThisSegment = configuration->get_number_of_packets_per_dpo_message(); + } + + const std::array buffer{ + DATA_PACKET_OFFSET_MULTIPLXOR, + packetsThisSegment, + static_cast(session->get_last_packet_number()), + static_cast((session->get_last_packet_number() >> 8) & 0xFF), + static_cast((session->get_last_packet_number() >> 16) & 0xFF), + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + bool retVal = sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + session->get_destination(), + CANIdentifier::CANPriority::PriorityLowest7); + if (retVal) + { + session->set_dpo_number_of_packets(packetsThisSegment); + session->set_sequence_number_offset(session->get_last_packet_number()); + session->set_last_sequency_number(0); + } + return retVal; + } + + bool ExtendedTransportProtocolManager::send_end_of_session_acknowledgement(std::shared_ptr &session) const + { + std::uint32_t messageLength = session->get_message_length(); + std::uint32_t parameterGroupNumber = session->get_parameter_group_number(); + + const std::array buffer{ + END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR, + static_cast(messageLength & 0xFF), + static_cast((messageLength >> 8) & 0xFF), + static_cast((messageLength >> 16) & 0xFF), + static_cast((messageLength >> 24) & 0xFF), + static_cast(parameterGroupNumber & 0xFF), + static_cast((parameterGroupNumber >> 8) & 0xFF), + static_cast((parameterGroupNumber >> 16) & 0xFF), + }; + + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::ExtendedTransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_destination()), // Since we're the receiving side, we are the destination of the session + session->get_source(), + CANIdentifier::CANPriority::PriorityLowest7); + } + + bool ExtendedTransportProtocolManager::has_session(std::shared_ptr source, std::shared_ptr destination) + { + return std::any_of(activeSessions.begin(), activeSessions.end(), [&](const std::shared_ptr &session) { + return session->matches(source, destination); + }); } -} // namespace isobus + std::shared_ptr ExtendedTransportProtocolManager::get_session(std::shared_ptr source, + std::shared_ptr destination) + { + auto result = std::find_if(activeSessions.begin(), activeSessions.end(), [&](const std::shared_ptr &session) { + return session->matches(source, destination); + }); + // Instead of returning a pointer, we return by reference to indicate it should not be deleted or stored + return (activeSessions.end() != result) ? (*result) : nullptr; + } + + const std::vector> &ExtendedTransportProtocolManager::get_sessions() const + { + return activeSessions; + } +} diff --git a/src/can_extended_transport_protocol.hpp b/src/can_extended_transport_protocol.hpp index 10dc18c..02702a5 100644 --- a/src/can_extended_transport_protocol.hpp +++ b/src/can_extended_transport_protocol.hpp @@ -2,234 +2,308 @@ /// @file can_extended_transport_protocol.hpp /// /// @brief A protocol class that handles the ISO11783 extended transport protocol. -/// Designed for packets larger than 1785 bytes. +/// Designed for destination specific packets larger than 1785 bytes. /// @author Adrian Del Grosso +/// @author Daan Steenbergen /// -/// @copyright 2022 Adrian Del Grosso +/// @copyright 2023 The Open-Agriculture Developers //================================================================================================ #ifndef CAN_EXTENDED_TRANSPORT_PROTOCOL_HPP #define CAN_EXTENDED_TRANSPORT_PROTOCOL_HPP -#include "can_badge.hpp" -#include "can_control_function.hpp" -#include "can_protocol.hpp" +#include "can_message_frame.hpp" +#include "can_network_configuration.hpp" +#include "can_transport_protocol_base.hpp" namespace isobus { - //================================================================================================ - /// @class ExtendedTransportProtocolManager - /// /// @brief A class that handles the ISO11783 extended transport protocol. /// @details This class handles transmission and reception of CAN messages more than 1785 bytes. - /// Simply call send_can_message on the network manager with an appropriate data length, - /// and the protocol will be automatically selected to be used. - //================================================================================================ - class ExtendedTransportProtocolManager : public CANLibProtocol + /// Simply call Simply call `CANNetworkManager::send_can_message()` + /// with an appropriate data length, and the protocol will be automatically selected to be used. + class ExtendedTransportProtocolManager { public: - /// @brief A list of all defined abort reasons in ISO11783 - enum class ConnectionAbortReason - { - Reserved = 0, ///< Reserved, not to be used, but should be tolerated - AlreadyInConnectionManagedSessionAndCannotSupportAnother = 1, ///< We are already in a session and can't support another - SystemResourcesNeededForAnotherTask = 2, ///< Session must be aborted because the system needs resources - Timeout = 3, ///< General timeout - ClearToSendReceivedWhenDataTransferInProgress = 4, ///< A CTS was received while already processing the last CTS - MaximumRetransmitRequestLimitReached = 5, ///< Maxmimum retries for the data has been reached - UnexpectedDataTransferPacket = 6, ///< A data packet was received outside the proper state - BadSequenceNumber = 7, ///< Incorrect sequence number was received and cannot be recovered - DuplicateSequenceNumber = 8, ///< Re-received a sequence number we've already processed - UnexpectedEDPOPacket = 9, ///< EDPO Received in an invalid state - UnexpectedEDPOPgn = 10, ///< Unexpected PGN in received EDPO - EDPONumberOfPacketsGreaterThanClearToSend = 11, ///< Number of EDPO packets is > CTS - BadEDPOOffset = 12, ///< EDPO offset was invalid - DeprecatedReason = 13, ///< Don't use this. Use AnyOtherReason instead - UnexpectedECTSPgn = 14, ///< PGN in received ECTS doesn't match session - ECTSRequestedPacketsExceedsMessageSize = 15, ///< ETP Can't support a message this large (CANMessage::ABSOLUTE_MAX_MESSAGE_LENGTH) - AnyOtherReason = 254 ///< Any other error not enumerated above, 0xFE - }; - /// @brief The states that a ETP session could be in. Used for the internal state machine. enum class StateMachineState { None, ///< Protocol session is not in progress - RequestToSend, ///< We are sending the request to send message + SendRequestToSend, ///< We are sending the request to send message WaitForClearToSend, ///< We are waiting for a clear to send message - RxDataSession, ///< We are receiving data packets - ClearToSend, ///< We are sending clear to send message - WaitForExtendedDataPacketOffset, ///< We are waiting for an EDPO message - TxDataSession, ///< We are transmitting EDPOs and data packets - WaitForEndOfMessageAcknowledge ///< We are waiting for an end of message acknowledgement + SendClearToSend, ///< We are sending clear to send message + WaitForDataPacketOffset, ///< We are waiting for a data packet offset message + SendDataPacketOffset, ///< We are sending a data packet offset message + WaitForDataTransferPacket, ///< We are waiting for data transfer packets + SendDataTransferPackets, ///< A Tx data session is in progress + WaitForEndOfMessageAcknowledge, ///< We are waiting for an end of message acknowledgement + }; + + /// @brief A list of all defined abort reasons in ISO11783 + enum class ConnectionAbortReason : std::uint8_t + { + Reserved = 0, ///< Reserved, not to be used, but should be tolerated + AlreadyInCMSession = 1, ///< We are already in a connection mode session and can't support another + SystemResourcesNeeded = 2, ///< Session must be aborted because the system needs resources + Timeout = 3, ///< General timeout + ClearToSendReceivedWhileTransferInProgress = 4, ///< A CTS was received while already processing the last CTS + MaximumRetransmitRequestLimitReached = 5, ///< Maximum retries for the data has been reached + UnexpectedDataTransferPacketReceived = 6, ///< A data packet was received outside the proper state + BadSequenceNumber = 7, ///< Incorrect sequence number was received and cannot be recovered + DuplicateSequenceNumber = 8, ///< Re-received a sequence number we've already processed + UnexpectedDataPacketOffsetReceived = 9, // Received a data packet offset outside the proper state + UnexpectedDataPacketOffsetPGN = 10, ///< Received a data packet offset with an unexpected PGN + DataPacketOffsetExceedsClearToSend = 11, ///< Received a number of packets in EDPO greater than CTS + BadDataPacketOffset = 12, ///< Received a data packet offset that is incorrect + UnexpectedClearToSendPGN = 14, ///< Received a CTS with an unexpected PGN + NumberOfClearToSendPacketsExceedsMessage = 15, ///< Received a CTS with a number of packets greater than the message + AnyOtherError = 250 ///< Any reason not defined in the standard }; - //================================================================================================ - /// @class ExtendedTransportProtocolSession - /// /// @brief A storage object to keep track of session information internally - //================================================================================================ - class ExtendedTransportProtocolSession + class ExtendedTransportProtocolSession : public TransportProtocolSessionBase { public: - /// @brief Enumerates the possible session directions, Rx or Tx - enum class Direction - { - Transmit, ///< We are transmitting a message - Receive ///< We are receving a message - }; + using TransportProtocolSessionBase::TransportProtocolSessionBase; ///< Inherit the base constructor - /// @brief A useful way to compare sesson objects to each other for equality - bool operator==(const ExtendedTransportProtocolSession &obj); + /// @brief Get the state of the session + /// @return The state of the session + StateMachineState get_state() const; - /// @brief Get the total number of bytes that will be sent or received in this session - /// @return The length of the message in number of bytes - std::uint32_t get_message_data_length() const; + /// @brief Get the number of bytes that have been sent or received in this session + /// @return The number of bytes that have been sent or received + std::uint32_t get_total_bytes_transferred() const override; - private: + protected: friend class ExtendedTransportProtocolManager; ///< Allows the ETP manager full access - /// @brief The constructor for an ETP session - /// @param[in] sessionDirection Tx or Rx - /// @param[in] canPortIndex The CAN channel index for the session - ExtendedTransportProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex); + /// @brief Set the state of the session + /// @param[in] value The state to set the session to + void set_state(StateMachineState value); + + /// @brief Get the number of packets to be sent with the current DPO + /// @return The number of packets to be sent with the current DPO + std::uint8_t get_dpo_number_of_packets_remaining() const; - /// @brief The destructor for a ETP session - ~ExtendedTransportProtocolSession(); + /// @brief Set the number of packets to be sent with the current DPO + /// @param[in] value The number of packets to be sent with the current DPO + void set_dpo_number_of_packets(std::uint8_t value); + /// @brief Get the number of packets that will be sent with the current DPO + /// @return The number of packets that will be sent with the current DPO + std::uint8_t get_dpo_number_of_packets() const; + + /// @brief Get the maximum number of packets that can be sent per DPO as indicated by the CTS message + /// @return The maximum number of packets that can be sent per DPO as indicated by the CTS message + std::uint8_t get_cts_number_of_packet_limit() const; + + /// @brief Set the maximum number of packets that can be sent per DPO as indicated by the CTS message + /// @param value The maximum number of packets that can be sent per DPO as indicated by the CTS message + void set_cts_number_of_packet_limit(std::uint8_t value); + + /// @brief Get the last sequence number that was processed + /// @return The last sequence number that was processed + std::uint8_t get_last_sequence_number() const; + + /// @brief Get the last packet number that was processed + /// @return The last packet number that was processed + std::uint32_t get_last_packet_number() const; + + /// @brief Set the last packet number that was processed + /// @param[in] value The last packet number that was processed + void set_sequence_number_offset(std::uint32_t value); + + /// @brief Set the last sequence number that has be processed + /// @param[in] value The last sequence number that has be processed + void set_last_sequency_number(std::uint8_t value); + + /// @brief Set the last acknowledged packet number by the receiver + /// @param[in] value The last acknowledged packet number by the receiver + void set_acknowledged_packet_number(std::uint32_t value); + + /// @brief Get the last acknowledged packet number by the receiver + /// @return The last acknowledged packet number by the receiver + std::uint32_t get_last_acknowledged_packet_number() const; + + /// @brief Get the number of packets that remain to be sent or received in this session + /// @return The number of packets that remain to be sent or received in this session + std::uint32_t get_number_of_remaining_packets() const; + + /// @brief Get the total number of packets that will be sent or received in this session + /// @return The total number of packets that will be sent or received in this session + std::uint32_t get_total_number_of_packets() const; + + private: StateMachineState state = StateMachineState::None; ///< The state machine state for this session - CANMessage sessionMessage; ///< A CAN message is used in the session to represent and store data like PGN - TransmitCompleteCallback sessionCompleteCallback = nullptr; ///< A callback that is to be called when the session is completed - DataChunkCallback frameChunkCallback = nullptr; ///< A callback that might be used to get chunks of data to send - std::uint32_t frameChunkCallbackMessageLength = 0; ///< The length of the message that is being sent in chunks - void *parent = nullptr; ///< A generic context variable that helps identify what object callbacks are destined for. Can be nullptr - std::uint32_t timestamp_ms = 0; ///< A timestamp used to track session timeouts - std::uint32_t lastPacketNumber = 0; ///< The last processed sequence number for this set of packets - std::uint32_t packetCount = 0; ///< The total number of packets to receive or send in this session - std::uint32_t processedPacketsThisSession = 0; ///< The total processed packet count for the whole session so far - const Direction sessionDirection; ///< Represents Tx or Rx session + + std::uint32_t lastAcknowledgedPacketNumber = 0; ///< The last acknowledged packet number by the receiver + std::uint32_t sequenceNumberOffset = 0; ///< The offset of the sequence number relative to the packet number + std::uint8_t lastSequenceNumber = 0; ///< The last processed sequence number for this set of packets + std::uint8_t dataPacketOffsetPacketCount = 0; ///< The number of packets that will be sent with the current DPO + std::uint8_t clearToSendPacketCountLimit = 0xFF; ///< The max packets that can be sent per DPO as indicated by the CTS message }; - /// @brief The constructor for the TransportProtocolManager - ExtendedTransportProtocolManager(); + static constexpr std::uint32_t REQUEST_TO_SEND_MULTIPLEXOR = 0x14; ///< (20) ETP.CM_RTS Multiplexor + static constexpr std::uint32_t CLEAR_TO_SEND_MULTIPLEXOR = 0x15; ///< (21) ETP.CM_CTS Multiplexor + static constexpr std::uint32_t DATA_PACKET_OFFSET_MULTIPLXOR = 0x16; ///< (22) ETP.CM_DPO Multiplexor + static constexpr std::uint32_t END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR = 0x17; ///< (23) TP.CM_EOMA Multiplexor + static constexpr std::uint32_t CONNECTION_ABORT_MULTIPLEXOR = 0xFF; ///< (255) Abort multiplexor + static constexpr std::uint32_t MAX_PROTOCOL_DATA_LENGTH = 117440505; ///< The max number of bytes that this protocol can transfer + static constexpr std::uint16_t T1_TIMEOUT_MS = 750; ///< The t1 timeout as defined by the standard + static constexpr std::uint16_t T2_T3_TIMEOUT_MS = 1250; ///< The t2/t3 timeouts as defined by the standard + static constexpr std::uint16_t T4_TIMEOUT_MS = 1050; ///< The t4 timeout as defined by the standard + static constexpr std::uint8_t TR_TIMEOUT_MS = 200; ///< The Tr Timeout as defined by the standard + static constexpr std::uint8_t SEQUENCE_NUMBER_DATA_INDEX = 0; ///< The index of the sequence number in a frame + static constexpr std::uint8_t PROTOCOL_BYTES_PER_FRAME = 7; ///< The number of payload bytes per frame minus overhead of sequence number - /// @brief The destructor for the TransportProtocolManager - ~ExtendedTransportProtocolManager() final; + /// @brief The constructor for the ExtendedTransportProtocolManager, for advanced use only. + /// In most cases, you should use the CANNetworkManager::send_can_message() function to transmit messages. + /// @param[in] sendCANFrameCallback A callback for sending a CAN frame to hardware + /// @param[in] canMessageReceivedCallback A callback for when a complete CAN message is received using the ETP protocol + /// @param[in] configuration The configuration to use for this protocol + ExtendedTransportProtocolManager(const CANMessageFrameCallback &sendCANFrameCallback, + const CANMessageCallback &canMessageReceivedCallback, + const CANNetworkConfiguration *configuration); - /// @brief The protocol's initializer function - void initialize(CANLibBadge) override; + /// @brief Updates all sessions managed by this protocol manager instance. + void update(); - /// @brief A generic way for a protocol to process a received message - /// @param[in] message A received CAN message - void process_message(const CANMessage &message) override; + /// @brief Checks if the source and destination control function have an active session/connection. + /// @param[in] source The source control function for the session + /// @param[in] destination The destination control function for the session + /// @returns true if a matching session was found, false if not + bool has_session(std::shared_ptr source, std::shared_ptr destination); + + /// @brief Gets all the active transport protocol sessions that are currently active + /// @note The list returns pointers to the transport protocol sessions, but they can disappear at any time + /// @returns A list of all the active transport protocol sessions + const std::vector> &get_sessions() const; /// @brief A generic way for a protocol to process a received message /// @param[in] message A received CAN message - /// @param[in] parent Provides the context to the actual TP manager object - static void process_message(const CANMessage &message, void *parent); + void process_message(const CANMessage &message); /// @brief The network manager calls this to see if the protocol can accept a long CAN message for processing /// @param[in] parameterGroupNumber The PGN of the message /// @param[in] data The data to be sent - /// @param[in] messageLength The length of the data to be sent /// @param[in] source The source control function /// @param[in] destination The destination control function - /// @param[in] transmitCompleteCallback A callback for when the protocol completes its work + /// @param[in] sessionCompleteCallback A callback for when the protocol completes its work /// @param[in] parentPointer A generic context object for the tx complete and chunk callbacks - /// @param[in] frameChunkCallback A callback to get some data to send /// @returns true if the message was accepted by the protocol for processing bool protocol_transmit_message(std::uint32_t parameterGroupNumber, - const std::uint8_t *data, - std::uint32_t messageLength, + std::unique_ptr &data, std::shared_ptr source, std::shared_ptr destination, - TransmitCompleteCallback transmitCompleteCallback, - void *parentPointer, - DataChunkCallback frameChunkCallback) override; - - /// @brief Updates the protocol cyclically - void update(CANLibBadge) override; + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer); private: - static constexpr std::uint32_t MAX_PROTOCOL_DATA_LENGTH = CANMessage::ABSOLUTE_MAX_MESSAGE_LENGTH; ///< The max payload this protocol can support - static constexpr std::uint32_t MIN_PROTOCOL_DATA_LENGTH = 1786; ///< The min payload this protocol can support - static constexpr std::uint32_t TR_TIMEOUT_MS = 200; ///< The Tr timeout as defined by the standard - static constexpr std::uint32_t T1_TIMEOUT_MS = 750; ///< The t1 timeout as defined by the standard - static constexpr std::uint32_t T2_3_TIMEOUT_MS = 1250; ///< The t2/t3 timeouts as defined by the standard - static constexpr std::uint32_t TH_TIMEOUT_MS = 500; ///< The Th timeout as defined by the standard - static constexpr std::uint8_t EXTENDED_REQUEST_TO_SEND_MULTIPLEXOR = 0x14; ///< The multiplexor for the extended request to send message - static constexpr std::uint8_t EXTENDED_CLEAR_TO_SEND_MULTIPLEXOR = 0x15; ///< The multiplexor for the extended clear to send message - static constexpr std::uint8_t EXTENDED_DATA_PACKET_OFFSET_MULTIPLEXOR = 0x16; ///< The multiplexor for the extended data packet offset message - static constexpr std::uint8_t EXTENDED_END_OF_MESSAGE_ACKNOWLEDGEMENT = 0x17; ///< Multiplexor for the extended end of message acknowledgement message - static constexpr std::uint8_t EXTENDED_CONNECTION_ABORT_MULTIPLEXOR = 0xFF; ///< Multiplexor for the extended connection abort message - static constexpr std::uint8_t PROTOCOL_BYTES_PER_FRAME = 7; ///< The number of payload bytes per frame minus overhead of sequence number - static constexpr std::uint8_t SEQUENCE_NUMBER_DATA_INDEX = 0; ///< The index of the sequence number in a frame - /// @brief Aborts the session with the specified abort reason. Sends a CAN message. /// @param[in] session The session to abort /// @param[in] reason The reason we're aborting the session /// @returns true if the abort was send OK, false if not sent - bool abort_session(ExtendedTransportProtocolSession *session, ConnectionAbortReason reason); + bool abort_session(std::shared_ptr &session, ConnectionAbortReason reason); - /// @brief Aborts Tp with no corresponding session with the specified abort reason. Sends a CAN message. + /// @brief Send an abort with no corresponding session with the specified abort reason. Sends a CAN message. + /// @param[in] sender The sender of the abort + /// @param[in] receiver The receiver of the abort /// @param[in] parameterGroupNumber The PGN of the ETP "session" we're aborting /// @param[in] reason The reason we're aborting the session - /// @param[in] source The source control function from which we'll send the abort - /// @param[in] destination The destination control function to which we'll send the abort - bool abort_session(std::uint32_t parameterGroupNumber, ConnectionAbortReason reason, std::shared_ptr source, std::shared_ptr destination); + /// @returns true if the abort was send OK, false if not sent + bool send_abort(std::shared_ptr sender, + std::shared_ptr receiver, + std::uint32_t parameterGroupNumber, + ConnectionAbortReason reason) const; /// @brief Gracefully closes a session to prepare for a new session /// @param[in] session The session to close - /// @param[in] successfull True if the session was closed successfully, false if not - void close_session(ExtendedTransportProtocolSession *session, bool successfull); - - /// @brief Gets an ETP session from the passed in source and destination combination - /// @param[in] source The source control function for the session - /// @param[in] destination The destination control function for the session - /// @param[out] session The found session, or nullptr if no session matched the supplied parameters - bool get_session(ExtendedTransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination) const; - - /// @brief Gets an ETP session from the passed in source and destination and PGN combination - /// @param[in] source The source control function for the session - /// @param[in] destination The destination control function for the session - /// @param[in] parameterGroupNumber The PGN of the session - /// @param[out] session The found session, or nullptr if no session matched the supplied parameters - bool get_session(ExtendedTransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination, std::uint32_t parameterGroupNumber) const; - - /// @brief Processes end of session callbacks - /// @param[in] session The session we've just completed - /// @param[in] success Denotes if the session was successful - void process_session_complete_callback(ExtendedTransportProtocolSession *session, bool success); + /// @param[in] successful Denotes if the session was successful + void close_session(std::shared_ptr &session, bool successful); - /// @brief Sends the "end of message acknowledgement" message for the provided session - /// @param[in] session The session for which we're sending the EOM ACK - /// @returns true if the EOM was sent, false if sending was not successful - bool send_end_of_session_acknowledgement(ExtendedTransportProtocolSession *session) const; // ETP.CM_EOMA + /// @brief Sends the "request to send" message as part of initiating a transmit + /// @param[in] session The session for which we're sending the RTS + /// @returns true if the RTS was sent, false if sending was not successful + bool send_request_to_send(std::shared_ptr &session) const; /// @brief Sends the "clear to send" message /// @param[in] session The session for which we're sending the CTS /// @returns true if the CTS was sent, false if sending was not successful - bool send_extended_connection_mode_clear_to_send(ExtendedTransportProtocolSession *session) const; // ETP.CM_CTS - - /// @brief Sends the "request to send" message as part of initiating a transmit - /// @param[in] session The session for which we're sending the RTS - /// @returns true if the RTS was sent, false if sending was not successful - bool send_extended_connection_mode_request_to_send(const ExtendedTransportProtocolSession *session) const; // ETP.CM_RTS + bool send_clear_to_send(std::shared_ptr &session) const; - /// @brief Sends the data packet offset message for the supplied session - /// @param[in] session The session for which we're sending the EDPO - /// @returns true if the EDPO was sent, false if sending was not successful - bool send_extended_connection_mode_data_packet_offset(const ExtendedTransportProtocolSession *session) const; // ETP.CM_DPO + /// @brief Sends the "data packet offset" message for the provided session + /// @param[in] session The session for which we're sending the DPO + /// @returns true if the DPO was sent, false if sending was not successful + bool send_data_packet_offset(std::shared_ptr &session) const; - /// @brief Sets the state machine state of the ETP session - /// @param[in] session The session to update - /// @param[in] value The state to update the session to - void set_state(ExtendedTransportProtocolSession *session, StateMachineState value); + /// @brief Sends the "end of message acknowledgement" message for the provided session + /// @param[in] session The session for which we're sending the EOM ACK + /// @returns true if the EOM was sent, false if sending was not successful + bool send_end_of_session_acknowledgement(std::shared_ptr &session) const; + + ///@brief Sends data transfer packets for the specified ExtendedTransportProtocolSession. + /// @param[in] session The ExtendedTransportProtocolSession for which to send data transfer packets. + void send_data_transfer_packets(std::shared_ptr &session) const; + + /// @brief Processes a request to send a message over the CAN transport protocol. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The Parameter Group Number of the message. + /// @param[in] totalMessageSize The total size of the message in bytes. + void process_request_to_send(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint32_t totalMessageSize); + + /// @brief Processes the Clear To Send (CTS) message. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The Parameter Group Number (PGN) of the message. + /// @param[in] packetsToBeSent The number of packets to be sent. + /// @param[in] nextPacketNumber The next packet number. + void process_clear_to_send(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint8_t packetsToBeSent, std::uint32_t nextPacketNumber); + + /// @brief Processes the Data Packet Offset (DPO) message. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The Parameter Group Number (PGN) of the message. + /// @param[in] numberOfPackets The number of packets that will follow. + /// @param[in] packetOffset The packet offset (always 1 less than CTS next packet number) + void process_data_packet_offset(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint8_t numberOfPackets, std::uint32_t packetOffset); + + /// @brief Processes the end of session acknowledgement. + /// @param[in] source The source control function. + /// @param[in] destination The destination control function. + /// @param[in] parameterGroupNumber The parameter group number. + /// @param[in] numberOfBytesTransferred The number of bytes transferred. + void process_end_of_session_acknowledgement(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint32_t numberOfBytesTransferred); + + /// @brief Processes an abort message in the CAN transport protocol. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The PGN (Parameter Group Number) of the message. + /// @param[in] reason The reason for the connection abort. + void process_abort(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, ExtendedTransportProtocolManager::ConnectionAbortReason reason); + + /// @brief Processes a connection management message. + /// @param[in] message The CAN message to be processed. + void process_connection_management_message(const CANMessage &message); + + /// @brief Processes a data transfer message. + /// @param[in] message The CAN message to be processed. + void process_data_transfer_message(const CANMessage &message); + + /// @brief Gets a ETP session from the passed in source and destination and PGN combination + /// @param[in] source The source control function for the session + /// @param[in] destination The destination control function for the session + /// @returns a matching session, or nullptr if no session matched the supplied parameters + std::shared_ptr get_session(std::shared_ptr source, std::shared_ptr destination); - /// @brief Updates the state machine of a ETP session + /// @brief Update the state machine for the passed in session /// @param[in] session The session to update - void update_state_machine(ExtendedTransportProtocolSession *session); + void update_state_machine(std::shared_ptr &session); - std::vector activeSessions; ///< A list of all active TP sessions + std::vector> activeSessions; ///< A list of all active ETP sessions + const CANMessageFrameCallback sendCANFrameCallback; ///< A callback for sending a CAN frame + const CANMessageCallback canMessageReceivedCallback; ///< A callback for when a complete CAN message is received using the ETP protocol + const CANNetworkConfiguration *configuration; ///< The configuration to use for this protocol }; } // namespace isobus diff --git a/src/can_general_parameter_group_numbers.hpp b/src/can_general_parameter_group_numbers.hpp index 5cd421a..ebbfb38 100644 --- a/src/can_general_parameter_group_numbers.hpp +++ b/src/can_general_parameter_group_numbers.hpp @@ -28,8 +28,8 @@ namespace isobus ECUtoVirtualTerminal = 0xE700, Acknowledge = 0xE800, ParameterGroupNumberRequest = 0xEA00, - TransportProtocolData = 0xEB00, - TransportProtocolCommand = 0xEC00, + TransportProtocolDataTransfer = 0xEB00, + TransportProtocolConnectionManagement = 0xEC00, AddressClaim = 0xEE00, ProprietaryA = 0xEF00, MachineSelectedSpeed = 0xF022, @@ -49,7 +49,14 @@ namespace isobus DiagnosticMessage11 = 0xFED3, CommandedAddress = 0xFED8, SoftwareIdentification = 0xFEDA, - AllImplementsStopOperationsSwitchState = 0xFD02 + AllImplementsStopOperationsSwitchState = 0xFD02, + VesselHeading = 0x1F112, + RateOfTurn = 0x1F113, + PositionRapidUpdate = 0x1F801, + CourseOverGroundSpeedOverGroundRapidUpdate = 0x1F802, + PositionDeltaHighPrecisionRapidUpdate = 0x1F803, + GNSSPositionData = 0x1F805, + Datum = 0x1F814 }; } // namespace isobus diff --git a/src/can_hardware_abstraction.hpp b/src/can_hardware_abstraction.hpp index 94d52d3..ff620f6 100644 --- a/src/can_hardware_abstraction.hpp +++ b/src/can_hardware_abstraction.hpp @@ -18,6 +18,7 @@ namespace isobus { /// @brief The sending abstraction layer between the hardware and the stack /// @param[in] frame The frame to transmit from the hardware + /// @returns true if the frame was successfully sent, false otherwise bool send_can_message_frame_to_hardware(const CANMessageFrame &frame); /// @brief The receiving abstraction layer between the hardware and the stack diff --git a/src/can_hardware_interface_single_thread.cpp b/src/can_hardware_interface_single_thread.cpp index 136738e..6247a5c 100644 --- a/src/can_hardware_interface_single_thread.cpp +++ b/src/can_hardware_interface_single_thread.cpp @@ -29,7 +29,7 @@ namespace isobus return CANHardwareInterface::transmit_can_frame(frame); } - bool CANHardwareInterface::set_number_of_can_channels(uint8_t value) + bool CANHardwareInterface::set_number_of_can_channels(std::uint8_t value) { if (started) { @@ -39,7 +39,7 @@ namespace isobus while (value > hardwareChannels.size()) { - hardwareChannels.push_back(std::make_unique()); + hardwareChannels.emplace_back(new CANHardware()); hardwareChannels.back()->frameHandler = nullptr; } while (value < hardwareChannels.size()) @@ -248,7 +248,7 @@ namespace isobus } else { - isobus::CANStackLogger::CAN_stack_log(isobus::CANStackLogger::LoggingLevel::Critical, "[CAN Rx Thread]: CAN Channel " + isobus::to_string(channelIndex) + " appears to be invalid."); + isobus::CANStackLogger::critical("[CAN Rx Thread]: CAN Channel " + isobus::to_string(channelIndex) + " appears to be invalid."); } } } @@ -263,4 +263,4 @@ namespace isobus } return retVal; } -} // namespace isobus \ No newline at end of file +} // namespace isobus diff --git a/src/can_hardware_interface_single_thread.hpp b/src/can_hardware_interface_single_thread.hpp index c73a83a..4027563 100644 --- a/src/can_hardware_interface_single_thread.hpp +++ b/src/can_hardware_interface_single_thread.hpp @@ -116,6 +116,7 @@ namespace isobus /// @brief Attempts to write a frame using the driver assigned to a frame's channel /// @param[in] frame The frame to try and write to the bus + /// @returns `true` if the frame was transmitted, otherwise `false` static bool transmit_can_frame_from_buffer(const isobus::CANMessageFrame &frame); static isobus::EventDispatcher frameReceivedEventDispatcher; ///< The event dispatcher for when a CAN message frame is received from hardware event diff --git a/src/can_hardware_plugin.hpp b/src/can_hardware_plugin.hpp index a4da8bb..47ea94b 100644 --- a/src/can_hardware_plugin.hpp +++ b/src/can_hardware_plugin.hpp @@ -27,10 +27,11 @@ namespace isobus /// @returns `true` if the driver is good/connected, `false` if the driver is not usable virtual bool get_is_valid() const = 0; - /// @brief Disconnects the driver from the hardware + /// @brief Disconnects the driver from the hardware. virtual void close() = 0; - /// @brief Connects the driver to the hardware + /// @brief Connects the driver to the hardware. This will be called to initialize the driver + /// and connect it to the hardware. virtual void open() = 0; /// @brief Reads one frame from the bus synchronously diff --git a/src/can_identifier.cpp b/src/can_identifier.cpp index c3411b4..3e91893 100644 --- a/src/can_identifier.cpp +++ b/src/can_identifier.cpp @@ -42,21 +42,6 @@ namespace isobus m_RawIdentifier |= static_cast(sourceAddress); } - CANIdentifier::CANIdentifier(const CANIdentifier &copiedObject) - { - m_RawIdentifier = copiedObject.m_RawIdentifier; - } - - CANIdentifier::~CANIdentifier() - { - } - - CANIdentifier &CANIdentifier::operator=(const CANIdentifier &obj) - { - m_RawIdentifier = obj.m_RawIdentifier; - return *this; - } - CANIdentifier::CANPriority CANIdentifier::get_priority() const { const std::uint8_t EXTENDED_IDENTIFIER_MASK = 0x07; diff --git a/src/can_identifier.hpp b/src/can_identifier.hpp index 5623c55..bfcda1b 100644 --- a/src/can_identifier.hpp +++ b/src/can_identifier.hpp @@ -24,7 +24,7 @@ namespace isobus { public: /// @brief Defines all the CAN frame priorities that can be encoded in a frame ID - enum CANPriority + enum class CANPriority { PriorityHighest0 = 0, ///< Highest CAN priority Priority1 = 1, ///< Priority highest - 1 @@ -37,7 +37,7 @@ namespace isobus }; /// @brief Defines if a frame is a standard (11 bit) or extended (29 bit) ID frame - enum Type + enum class Type { Standard = 0, ///< Frame is an 11bit ID standard (legacy) message with no PGN and highest priority Extended = 1 ///< Frame is a modern 29 bit ID CAN frame @@ -59,16 +59,8 @@ namespace isobus std::uint8_t destinationAddress, std::uint8_t sourceAddress); - /// @brief Copy constructor for a CAN Identifier - /// @param[in] copiedObject The object to copy - CANIdentifier(const CANIdentifier &copiedObject); - /// @brief Destructor for the CANIdentifier - ~CANIdentifier(); - - /// @brief Assignment operator for a CAN identifier - /// @param[in] obj rhs of the operator - CANIdentifier &operator=(const CANIdentifier &obj); + ~CANIdentifier() = default; /// @brief Returns the raw encoded ID of the CAN identifier /// @returns The raw encoded ID of the CAN identifier diff --git a/src/can_internal_control_function.cpp b/src/can_internal_control_function.cpp index 67fa0c7..ab3fe12 100644 --- a/src/can_internal_control_function.cpp +++ b/src/can_internal_control_function.cpp @@ -29,7 +29,7 @@ namespace isobus // Unfortunately, we can't use `std::make_shared` here because the constructor is private CANLibBadge badge; // This badge is used to allow creation of the PGN request protocol only from within this class auto controlFunction = std::shared_ptr(new InternalControlFunction(desiredName, preferredAddress, CANPort, badge)); - controlFunction->pgnRequestProtocol = std::make_unique(controlFunction, badge); + controlFunction->pgnRequestProtocol.reset(new ParameterGroupNumberRequestProtocol(controlFunction, badge)); CANNetworkManager::CANNetwork.on_control_function_created(controlFunction, badge); return controlFunction; } diff --git a/src/can_internal_control_function.hpp b/src/can_internal_control_function.hpp index ed175c9..74a4696 100644 --- a/src/can_internal_control_function.hpp +++ b/src/can_internal_control_function.hpp @@ -38,6 +38,7 @@ namespace isobus /// @param[in] desiredName The NAME for this control function to claim as /// @param[in] preferredAddress The preferred NAME for this control function /// @param[in] CANPort The CAN channel index for this control function to use + /// @returns A shared pointer to an InternalControlFunction object created with the parameters passed in static std::shared_ptr create(NAME desiredName, std::uint8_t preferredAddress, std::uint8_t CANPort); /// @brief Destroys this control function, by removing it from the network manager @@ -57,6 +58,7 @@ namespace isobus /// @brief Used by the network manager to tell the ICF that the address claim state machine needs to process /// a J1939 command to move address. + /// @param[in] commandedAddress The address that the ICF has been commanded to move to void process_commanded_address(std::uint8_t commandedAddress, CANLibBadge); /// @brief Updates the internal control function together with it's associated address claim state machine diff --git a/src/can_message.cpp b/src/can_message.cpp index 8ff536c..09d49f5 100644 --- a/src/can_message.cpp +++ b/src/can_message.cpp @@ -14,11 +14,42 @@ namespace isobus { - CANMessage::CANMessage(std::uint8_t CANPort) : + CANMessage::CANMessage(Type type, + CANIdentifier identifier, + const std::uint8_t *dataBuffer, + std::uint32_t length, + std::shared_ptr source, + std::shared_ptr destination, + std::uint8_t CANPort) : + messageType(type), + identifier(identifier), + data(dataBuffer, dataBuffer + length), + source(source), + destination(destination), CANPortIndex(CANPort) { } + CANMessage::CANMessage(Type type, + CANIdentifier identifier, + std::vector data, + std::shared_ptr source, + std::shared_ptr destination, + std::uint8_t CANPort) : + messageType(type), + identifier(identifier), + data(std::move(data)), + source(source), + destination(destination), + CANPortIndex(CANPort) + { + } + + CANMessage CANMessage::create_invalid_message() + { + return CANMessage(CANMessage::Type::Receive, CANIdentifier(CANIdentifier::UNDEFINED_PARAMETER_GROUP_NUMBER), {}, nullptr, nullptr, 0); + } + CANMessage::Type CANMessage::get_type() const { return messageType; @@ -39,16 +70,51 @@ namespace isobus return source; } + bool CANMessage::has_valid_source_control_function() const + { + return (nullptr != source) && source->get_address_valid(); + } + std::shared_ptr CANMessage::get_destination_control_function() const { return destination; } + bool CANMessage::has_valid_destination_control_function() const + { + return (nullptr != destination) && destination->get_address_valid(); + } + + bool CANMessage::is_broadcast() const + { + return (!has_valid_destination_control_function()) || (destination->get_address() == CANIdentifier::GLOBAL_ADDRESS); + } + + bool CANMessage::is_destination_our_device() const + { + return has_valid_destination_control_function() && destination->get_type() == ControlFunction::Type::Internal; + } + + bool CANMessage::is_destination(std::shared_ptr controlFunction) const + { + return has_valid_destination_control_function() && destination == controlFunction; + } + + bool CANMessage::is_source(std::shared_ptr controlFunction) const + { + return has_valid_source_control_function() && source == controlFunction; + } + CANIdentifier CANMessage::get_identifier() const { return identifier; } + bool CANMessage::is_parameter_group_number(CANLibParameterGroupNumber parameterGroupNumber) const + { + return identifier.get_parameter_group_number() == static_cast(parameterGroupNumber); + } + std::uint8_t CANMessage::get_can_port_index() const { return CANPortIndex; @@ -74,17 +140,7 @@ namespace isobus data.resize(length); } - void CANMessage::set_source_control_function(std::shared_ptr value) - { - source = value; - } - - void CANMessage::set_destination_control_function(std::shared_ptr value) - { - destination = value; - } - - void CANMessage::set_identifier(CANIdentifier value) + void CANMessage::set_identifier(const CANIdentifier &value) { identifier = value; } @@ -94,6 +150,11 @@ namespace isobus return data.at(index); } + std::int8_t CANMessage::get_int8_at(const std::uint32_t index) const + { + return static_cast(data.at(index)); + } + std::uint16_t CANMessage::get_uint16_at(const std::uint32_t index, const ByteFormat format) const { std::uint16_t retVal; @@ -110,6 +171,22 @@ namespace isobus return retVal; } + std::int16_t CANMessage::get_int16_at(const std::uint32_t index, const ByteFormat format) const + { + std::int16_t retVal; + if (ByteFormat::LittleEndian == format) + { + retVal = static_cast(data.at(index)); + retVal |= static_cast(data.at(index + 1)) << 8; + } + else + { + retVal = static_cast(data.at(index)) << 8; + retVal |= static_cast(data.at(index + 1)); + } + return retVal; + } + std::uint32_t CANMessage::get_uint24_at(const std::uint32_t index, const ByteFormat format) const { std::uint32_t retVal; @@ -128,6 +205,24 @@ namespace isobus return retVal; } + std::int32_t CANMessage::get_int24_at(const std::uint32_t index, const ByteFormat format) const + { + std::int32_t retVal; + if (ByteFormat::LittleEndian == format) + { + retVal = static_cast(data.at(index)); + retVal |= static_cast(data.at(index + 1)) << 8; + retVal |= static_cast(data.at(index + 2)) << 16; + } + else + { + retVal = static_cast(data.at(index + 2)) << 16; + retVal |= static_cast(data.at(index + 1)) << 8; + retVal |= static_cast(data.at(index + 2)); + } + return retVal; + } + std::uint32_t CANMessage::get_uint32_at(const std::uint32_t index, const ByteFormat format) const { std::uint32_t retVal; @@ -148,6 +243,26 @@ namespace isobus return retVal; } + std::int32_t CANMessage::get_int32_at(const std::uint32_t index, const ByteFormat format) const + { + std::int32_t retVal; + if (ByteFormat::LittleEndian == format) + { + retVal = static_cast(data.at(index)); + retVal |= static_cast(data.at(index + 1)) << 8; + retVal |= static_cast(data.at(index + 2)) << 16; + retVal |= static_cast(data.at(index + 3)) << 24; + } + else + { + retVal = static_cast(data.at(index)) << 24; + retVal |= static_cast(data.at(index + 1)) << 16; + retVal |= static_cast(data.at(index + 2)) << 8; + retVal |= static_cast(data.at(index + 3)); + } + return retVal; + } + std::uint64_t CANMessage::get_uint64_at(const std::uint32_t index, const ByteFormat format) const { std::uint64_t retVal; @@ -175,6 +290,35 @@ namespace isobus } return retVal; } + + std::int64_t CANMessage::get_int64_at(const std::uint32_t index, const ByteFormat format) const + { + std::int64_t retVal; + if (ByteFormat::LittleEndian == format) + { + retVal = static_cast(data.at(index)); + retVal |= static_cast(data.at(index + 1)) << 8; + retVal |= static_cast(data.at(index + 2)) << 16; + retVal |= static_cast(data.at(index + 3)) << 24; + retVal |= static_cast(data.at(index + 4)) << 32; + retVal |= static_cast(data.at(index + 5)) << 40; + retVal |= static_cast(data.at(index + 6)) << 48; + retVal |= static_cast(data.at(index + 7)) << 56; + } + else + { + retVal = static_cast(data.at(index)) << 56; + retVal |= static_cast(data.at(index + 1)) << 48; + retVal |= static_cast(data.at(index + 2)) << 40; + retVal |= static_cast(data.at(index + 3)) << 32; + retVal |= static_cast(data.at(index + 4)) << 24; + retVal |= static_cast(data.at(index + 5)) << 16; + retVal |= static_cast(data.at(index + 6)) << 8; + retVal |= static_cast(data.at(index + 7)); + } + return retVal; + } + bool isobus::CANMessage::get_bool_at(const std::uint32_t byteIndex, const std::uint8_t bitIndex, const std::uint8_t length) const { assert(length <= 8 - bitIndex && "length must be less than or equal to 8 - bitIndex"); diff --git a/src/can_message.hpp b/src/can_message.hpp index e8b217b..a00966f 100644 --- a/src/can_message.hpp +++ b/src/can_message.hpp @@ -12,12 +12,17 @@ #define CAN_MESSAGE_HPP #include "can_control_function.hpp" +#include "can_general_parameter_group_numbers.hpp" #include "can_identifier.hpp" +#include "data_span.hpp" #include namespace isobus { + /// @brief A read-only span of data for a CAN message + using CANDataSpan = DataSpan; + //================================================================================================ /// @class CANMessage /// @@ -31,7 +36,6 @@ namespace isobus { Transmit, ///< Message is to be transmitted from the stack Receive, ///< Message is being received - Internal ///< Message is being used internally as data storage for a protocol }; /// @brief The different byte formats that can be used when reading bytes from the buffer. @@ -47,12 +51,39 @@ namespace isobus /// @returns The maximum length of any CAN message as defined by ETP in ISO11783 static const std::uint32_t ABSOLUTE_MAX_MESSAGE_LENGTH = 117440505; - /// @brief Constructor for a CAN message - /// @param[in] CANPort The can channel index the message uses - explicit CANMessage(std::uint8_t CANPort); + /// @brief Construct a CAN message from the parameters supplied + /// @param[in] type The type of the CAN message + /// @param[in] identifier The CAN ID of the message + /// @param[in] dataBuffer The start of the data payload + /// @param[in] length The length of the data payload in bytes + /// @param[in] source The source control function of the message + /// @param[in] destination The destination control function of the message + /// @param[in] CANPort The CAN channel index associated with the message + CANMessage(Type type, + CANIdentifier identifier, + const std::uint8_t *dataBuffer, + std::uint32_t length, + std::shared_ptr source, + std::shared_ptr destination, + std::uint8_t CANPort); + + /// @brief Construct a CAN message from the parameters supplied + /// @param[in] type The type of the CAN message + /// @param[in] identifier The CAN ID of the message + /// @param[in] data The data payload + /// @param[in] source The source control function of the message + /// @param[in] destination The destination control function of the message + /// @param[in] CANPort The CAN channel index associated with the message + CANMessage(Type type, + CANIdentifier identifier, + std::vector data, + std::shared_ptr source, + std::shared_ptr destination, + std::uint8_t CANPort); - /// @brief Destructor for a CAN message - virtual ~CANMessage() = default; + /// @brief Factory method to construct an intentionally invalid CANMessage + /// @returns An invalid CANMessage + static CANMessage create_invalid_message(); /// @brief Returns the CAN message type /// @returns The type of the CAN message @@ -64,20 +95,51 @@ namespace isobus /// @brief Returns the length of the data in the CAN message /// @returns The message data payload length - virtual std::uint32_t get_data_length() const; + std::uint32_t get_data_length() const; /// @brief Gets the source control function that the message is from /// @returns The source control function that the message is from std::shared_ptr get_source_control_function() const; + /// @brief Returns whether the message is sent by a device that claimed its address on the bus. + /// @returns True if the source of the message is valid, false otherwise + bool has_valid_source_control_function() const; + /// @brief Gets the destination control function that the message is to /// @returns The destination control function that the message is to std::shared_ptr get_destination_control_function() const; + /// @brief Returns whether the message is sent to a specific device on the bus. + /// @returns True if the destination of the message is valid, false otherwise + bool has_valid_destination_control_function() const; + + /// @brief Returns whether the message is sent as a broadcast message / to all devices on the bus. + /// @returns True if the destination of the message is everyone, false otherwise + bool is_broadcast() const; + + /// @brief Returns whether the message is destined for our device on the bus. + /// @returns True if the message is destined for our device, false otherwise + bool is_destination_our_device() const; + + /// @brief Returns whether the message is destined for the control function. + /// @param[in] controlFunction The control function to check + /// @returns True if the message is destined for the control function, false otherwise + bool is_destination(std::shared_ptr controlFunction) const; + + /// @brief Returns whether the message is originated from the control function. + /// @param[in] controlFunction The control function to check + /// @returns True if the message is originated from the control function, false otherwise + bool is_source(std::shared_ptr controlFunction) const; + /// @brief Returns the identifier of the message /// @returns The identifier of the message CANIdentifier get_identifier() const; + /// @brief Compares the identifier of the message to the parameter group number (PGN) supplied + /// @param[in] parameterGroupNumber The parameter group number to compare to + /// @returns True if the message identifier matches the parameter group number, false otherwise + bool is_parameter_group_number(CANLibParameterGroupNumber parameterGroupNumber) const; + /// @brief Returns the CAN channel index associated with the message /// @returns The CAN channel index associated with the message std::uint8_t get_can_port_index() const; @@ -96,17 +158,9 @@ namespace isobus /// @param[in] length The desired length of the data payload void set_data_size(std::uint32_t length); - /// @brief Sets the source control function for the message - /// @param[in] value The source control function - void set_source_control_function(std::shared_ptr value); - - /// @brief Sets the destination control function for the message - /// @param[in] value The destination control function - void set_destination_control_function(std::shared_ptr value); - /// @brief Sets the CAN ID of the message /// @param[in] value The CAN ID for the message - void set_identifier(CANIdentifier value); + void set_identifier(const CANIdentifier &value); /// @brief Get a 8-bit unsigned byte from the buffer at a specific index. /// A 8-bit unsigned byte can hold a value between 0 and 255. @@ -115,6 +169,13 @@ namespace isobus /// @return The 8-bit unsigned byte std::uint8_t get_uint8_at(const std::uint32_t index) const; + /// @brief Get a 8-bit signed byte from the buffer at a specific index. + /// A 8-bit signed byte can hold a value between -128 and 127. + /// @details This function will return the byte at the specified index in the buffer. + /// @param[in] index The index to get the byte from + /// @return The 8-bit signed byte + std::int8_t get_int8_at(const std::uint32_t index) const; + /// @brief Get a 16-bit unsigned integer from the buffer at a specific index. /// A 16-bit unsigned integer can hold a value between 0 and 65535. /// @details This function will return the 2 bytes at the specified index in the buffer. @@ -123,6 +184,14 @@ namespace isobus /// @return The 16-bit unsigned integer std::uint16_t get_uint16_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a 16-bit signed integer from the buffer at a specific index. + /// A 16-bit signed integer can hold a value between -32768 and 32767. + /// @details This function will return the 2 bytes at the specified index in the buffer. + /// @param[in] index The index to get the 16-bit signed integer from + /// @param[in] format The byte format to use when reading the integer + /// @return The 16-bit signed integer + std::int16_t get_int16_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a right-aligned 24-bit integer from the buffer (returned as a uint32_t) at a specific index. /// A 24-bit number can hold a value between 0 and 16,777,215. /// @details This function will return the 3 bytes at the specified index in the buffer. @@ -131,6 +200,14 @@ namespace isobus /// @return The 24-bit unsigned integer, right aligned into a uint32_t std::uint32_t get_uint24_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a right-aligned 24-bit integer from the buffer (returned as a int32_t) at a specific index. + /// A 24-bit number can hold a value between -8388608 and 8388607. + /// @details This function will return the 3 bytes at the specified index in the buffer. + /// @param[in] index The index to get the 24-bit signed integer from + /// @param[in] format The byte format to use when reading the integer + /// @return The 24-bit signed integer, right aligned into a int32_t + std::int32_t get_int24_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a 32-bit unsigned integer from the buffer at a specific index. /// A 32-bit unsigned integer can hold a value between 0 and 4294967295. /// @details This function will return the 4 bytes at the specified index in the buffer. @@ -139,6 +216,14 @@ namespace isobus /// @return The 32-bit unsigned integer std::uint32_t get_uint32_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a 32-bit signed integer from the buffer at a specific index. + /// A 32-bit signed integer can hold a value between -2147483648 and 2147483647. + /// @details This function will return the 4 bytes at the specified index in the buffer. + /// @param[in] index The index to get the 32-bit signed integer from + /// @param[in] format The byte format to use when reading the integer + /// @return The 32-bit signed integer + std::int32_t get_int32_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a 64-bit unsigned integer from the buffer at a specific index. /// A 64-bit unsigned integer can hold a value between 0 and 18446744073709551615. /// @details This function will return the 8 bytes at the specified index in the buffer. @@ -147,6 +232,14 @@ namespace isobus /// @return The 64-bit unsigned integer std::uint64_t get_uint64_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a 64-bit signed integer from the buffer at a specific index. + /// A 64-bit signed integer can hold a value between -9223372036854775808 and 9223372036854775807. + /// @details This function will return the 8 bytes at the specified index in the buffer. + /// @param[in] index The index to get the 64-bit signed integer from + /// @param[in] format The byte format to use when reading the integer + /// @return The 64-bit signed integer + std::int64_t get_int64_at(const std::uint32_t index, const ByteFormat format = ByteFormat::LittleEndian) const; + /// @brief Get a bit-boolean from the buffer at a specific index. /// @details This function will return whether the bit(s) at the specified index in the buffer is/are (all) equal to 1. /// @param[in] byteIndex The byte index to start reading the boolean from @@ -156,12 +249,12 @@ namespace isobus bool get_bool_at(const std::uint32_t byteIndex, const std::uint8_t bitIndex, const std::uint8_t length = 1) const; private: - Type messageType = Type::Receive; ///< The internal message type associated with the message - CANIdentifier identifier = CANIdentifier(0); ///< The CAN ID of the message + Type messageType; ///< The internal message type associated with the message + CANIdentifier identifier; ///< The CAN ID of the message std::vector data; ///< A data buffer for the message, used when not using data chunk callbacks - std::shared_ptr source = nullptr; ///< The source control function of the message - std::shared_ptr destination = nullptr; ///< The destination control function of the message - const std::uint8_t CANPortIndex; ///< The CAN channel index associated with the message + std::shared_ptr source; ///< The source control function of the message + std::shared_ptr destination; ///< The destination control function of the message + std::uint8_t CANPortIndex; ///< The CAN channel index associated with the message }; } // namespace isobus diff --git a/src/can_message_data.cpp b/src/can_message_data.cpp new file mode 100644 index 0000000..214918d --- /dev/null +++ b/src/can_message_data.cpp @@ -0,0 +1,122 @@ +//================================================================================================ +/// @file can_message_data.hpp +/// +/// @brief An class that represents a CAN message of arbitrary length being transported. +/// @author Daan Steenbergen +/// +/// @copyright 2023 OpenAgriculture +//================================================================================================ + +#include "can_message_data.hpp" + +#include + +namespace isobus +{ + CANMessageDataVector::CANMessageDataVector(std::size_t size) + { + vector::resize(size); + } + + CANMessageDataVector::CANMessageDataVector(const std::vector &data) + { + vector::assign(data.begin(), data.end()); + } + + CANMessageDataVector::CANMessageDataVector(const std::uint8_t *data, std::size_t size) + { + vector::assign(data, data + size); + } + + std::size_t CANMessageDataVector::size() const + { + return vector::size(); + } + + std::uint8_t CANMessageDataVector::get_byte(std::size_t index) + { + return vector::at(index); + } + + void CANMessageDataVector::set_byte(std::size_t index, std::uint8_t value) + { + vector::at(index) = value; + } + + CANDataSpan CANMessageDataVector::data() const + { + return CANDataSpan(vector::data(), vector::size()); + } + + std::unique_ptr CANMessageDataVector::copy_if_not_owned(std::unique_ptr self) const + { + // We know that a CANMessageDataVector is always owned by itself, so we can just return itself. + return self; + } + + CANMessageDataView::CANMessageDataView(const std::uint8_t *ptr, std::size_t len) : + CANDataSpan(ptr, len) + { + } + + std::size_t CANMessageDataView::size() const + { + return DataSpan::size(); + } + + std::uint8_t CANMessageDataView::get_byte(std::size_t index) + { + return DataSpan::operator[](index); + } + + CANDataSpan CANMessageDataView::data() const + { + return CANDataSpan(DataSpan::begin(), DataSpan::size()); + } + + std::unique_ptr CANMessageDataView::copy_if_not_owned(std::unique_ptr) const + { + // A view doesn't own the data, so we need to make a copy. + return std::unique_ptr(new CANMessageDataVector(DataSpan::begin(), DataSpan::size())); + } + + CANMessageDataCallback::CANMessageDataCallback(std::size_t size, + DataChunkCallback callback, + void *parentPointer, + std::size_t chunkSize) : + totalSize(size), + callback(callback), + parentPointer(parentPointer), + buffer(chunkSize), + bufferSize(chunkSize) + { + } + + std::size_t CANMessageDataCallback::size() const + { + return totalSize; + } + + std::uint8_t CANMessageDataCallback::get_byte(std::size_t index) + { + if (index >= totalSize) + { + return 0; + } + + if ((index >= dataOffset + bufferSize) || (index < dataOffset) || (!initialized)) + { + initialized = true; + dataOffset = index; + callback(0, dataOffset, std::min(totalSize - dataOffset, bufferSize), buffer.data(), parentPointer); + } + return buffer[index - dataOffset]; + } + + std::unique_ptr CANMessageDataCallback::copy_if_not_owned(std::unique_ptr self) const + { + // A callback doesn't own it's data, but it does own the callback function, so we can just return itself. + return self; + } + +} // namespace isobus diff --git a/src/can_message_data.hpp b/src/can_message_data.hpp new file mode 100644 index 0000000..784f007 --- /dev/null +++ b/src/can_message_data.hpp @@ -0,0 +1,157 @@ +//================================================================================================ +/// @file can_message_data.hpp +/// +/// @brief An interface class that represents data payload of a CAN message of arbitrary length. +/// @author Daan Steenbergen +/// +/// @copyright 2023 - The OpenAgriculture Developers +//================================================================================================ + +#ifndef CAN_MESSAGE_DATA_HPP +#define CAN_MESSAGE_DATA_HPP + +#include "can_callbacks.hpp" +#include "can_control_function.hpp" +#include "can_message.hpp" +#include "data_span.hpp" + +#include +#include +#include + +namespace isobus +{ + /// @brief A interface class that represents data payload of a CAN message of arbitrary length. + class CANMessageData + { + public: + /// @brief Default destructor. + virtual ~CANMessageData() = default; + + /// @brief Get the size of the data. + /// @return The size of the data. + virtual std::size_t size() const = 0; + + /// @brief Get the byte at the given index. + /// @param[in] index The index of the byte to get. + /// @return The byte at the given index. + virtual std::uint8_t get_byte(std::size_t index) = 0; + + /// @brief If the data isn't owned by this class, make a copy of the data. + /// @param[in] self A pointer to this object. + /// @return A copy of the data if it isn't owned by this class, otherwise a moved pointer. + virtual std::unique_ptr copy_if_not_owned(std::unique_ptr self) const = 0; + }; + + /// @brief A class that represents data of a CAN message by holding a vector of bytes. + class CANMessageDataVector : public CANMessageData + , public std::vector + { + public: + /// @brief Construct a new CANMessageDataVector object. + /// @param[in] size The size of the data. + explicit CANMessageDataVector(std::size_t size); + + /// @brief Construct a new CANMessageDataVector object. + /// @param[in] data The data to copy. + explicit CANMessageDataVector(const std::vector &data); + + /// @brief Construct a new CANMessageDataVector object. + /// @param[in] data A pointer to the data to copy. + /// @param[in] size The size of the data to copy. + CANMessageDataVector(const std::uint8_t *data, std::size_t size); + + /// @brief Get the size of the data. + /// @return The size of the data. + std::size_t size() const override; + + /// @brief Get the byte at the given index. + /// @param[in] index The index of the byte to get. + /// @return The byte at the given index. + std::uint8_t get_byte(std::size_t index) override; + + /// @brief Set the byte at the given index. + /// @param[in] index The index of the byte to set. + /// @param[in] value The value to set the byte to. + void set_byte(std::size_t index, std::uint8_t value); + + /// @brief Get the data span. + /// @return The data span. + CANDataSpan data() const; + + /// @brief If the data isn't owned by this class, make a copy of the data. + /// @param[in] self A pointer to this object. + /// @return A copy of the data if it isn't owned by this class, otherwise it returns itself. + std::unique_ptr copy_if_not_owned(std::unique_ptr self) const override; + }; + + /// @brief A class that represents data of a CAN message by holding a view of an array of bytes. + /// The view is not owned by this class, it is simply holding a pointer to the array of bytes. + class CANMessageDataView : public CANMessageData + , public CANDataSpan + { + public: + /// @brief Construct a new CANMessageDataView object. + /// @param[in] ptr The pointer to the array of bytes. + /// @param[in] len The length of the array of bytes. + CANMessageDataView(const std::uint8_t *ptr, std::size_t len); + + /// @brief Get the size of the data. + /// @return The size of the data. + std::size_t size() const override; + + /// @brief Get the byte at the given index. + /// @param[in] index The index of the byte to get. + /// @return The byte at the given index. + std::uint8_t get_byte(std::size_t index) override; + + /// @brief Get the data span. + /// @return The data span. + CANDataSpan data() const; + + /// @brief If the data isn't owned by this class, make a copy of the data. + /// @param[in] self A pointer to this object. + /// @return A copy of the data if it isn't owned by this class, otherwise it returns itself. + std::unique_ptr copy_if_not_owned(std::unique_ptr self) const override; + }; + + /// @brief A class that represents data of a CAN message by using a callback function. + class CANMessageDataCallback : public CANMessageData + { + public: + /// @brief Constructor for transport data that uses a callback function. + /// @param[in] size The size of the data. + /// @param[in] callback The callback function to be called for each data chunk. + /// @param[in] parentPointer The parent object that owns this callback (optional). + /// @param[in] chunkSize The size of each data chunk (optional, default is 7). + CANMessageDataCallback(std::size_t size, + DataChunkCallback callback, + void *parentPointer = nullptr, + std::size_t chunkSize = 7); + + /// @brief Get the size of the data. + /// @return The size of the data. + std::size_t size() const override; + + /// @brief Get the byte at the given index. + /// @param[in] index The index of the byte to get. + /// @return The byte at the given index. + std::uint8_t get_byte(std::size_t index) override; + + /// @brief If the data isn't owned by this class, make a copy of the data. + /// @param[in] self A pointer to this object. + /// @return A copy of the data if it isn't owned by this class, otherwise it returns itself. + std::unique_ptr copy_if_not_owned(std::unique_ptr self) const override; + + private: + std::size_t totalSize; ///< The total size of the data. + DataChunkCallback callback; ///< The callback function to be called for each data chunk. + void *parentPointer; ///< The parent object that gets passed to the callback function. + std::vector buffer; ///< The buffer to store the data chunks. + std::size_t bufferSize; ///< The size of the buffer. + std::size_t dataOffset = 0; ///< The offset of the data in the buffer. + bool initialized = false; ///< Whether the buffer has been initialized. + }; +} // namespace isobus + +#endif // CAN_MESSAGE_DATA_HPP diff --git a/src/can_network_configuration.cpp b/src/can_network_configuration.cpp index 84f9a42..0fcc172 100644 --- a/src/can_network_configuration.cpp +++ b/src/can_network_configuration.cpp @@ -38,14 +38,14 @@ namespace isobus return minimumTimeBetweenTransportProtocolBAMFrames; } - void CANNetworkConfiguration::set_max_number_of_etp_frames_per_edpo(std::uint8_t numberFrames) + void CANNetworkConfiguration::set_number_of_packets_per_dpo_message(std::uint8_t numberFrames) { - extendedTransportProtocolMaxNumberOfFramesPerEDPO = numberFrames; + numberOfPacketsPerDPOMessage = numberFrames; } - std::uint8_t CANNetworkConfiguration::get_max_number_of_etp_frames_per_edpo() const + std::uint8_t CANNetworkConfiguration::get_number_of_packets_per_dpo_message() const { - return extendedTransportProtocolMaxNumberOfFramesPerEDPO; + return numberOfPacketsPerDPOMessage; } void CANNetworkConfiguration::set_max_number_of_network_manager_protocol_frames_per_update(std::uint8_t numberFrames) @@ -57,4 +57,14 @@ namespace isobus { return networkManagerMaxFramesToSendPerUpdate; } + + void CANNetworkConfiguration::set_number_of_packets_per_cts_message(std::uint8_t numberFrames) + { + numberOfPacketsPerCTSMessage = numberFrames; + } + + std::uint8_t CANNetworkConfiguration::get_number_of_packets_per_cts_message() const + { + return numberOfPacketsPerCTSMessage; + } } diff --git a/src/can_network_configuration.hpp b/src/can_network_configuration.hpp index 8b6cd12..e0a710f 100644 --- a/src/can_network_configuration.hpp +++ b/src/can_network_configuration.hpp @@ -38,6 +38,7 @@ namespace isobus std::uint32_t get_max_number_transport_protocol_sessions() const; /// @brief Sets the minimum time to wait between sending BAM frames + /// (default is 50 ms for maximum J1939 compatibility) /// @details The acceptable range as defined by ISO-11783 is 10 to 200 ms. /// This is a minumum time, so if you set it to some value, like 10 ms, the /// stack will attempt to transmit it as close to that time as it can, but it is @@ -50,16 +51,16 @@ namespace isobus std::uint32_t get_minimum_time_between_transport_protocol_bam_frames() const; /// @brief Sets the max number of data frames the stack will use when - /// in an ETP session, between EDPO phases. The default is 255, - /// but decreasing it may reduce bus load at the expense of transfer time. + /// in an ETP session, between EDPO phases. The default is 16. + /// Note that the sending control function may choose to use a lower number of frames. /// @param[in] numberFrames The max number of data frames to use - void set_max_number_of_etp_frames_per_edpo(std::uint8_t numberFrames); + void set_number_of_packets_per_dpo_message(std::uint8_t numberFrames); /// @brief Returns the max number of data frames the stack will use when - /// in an ETP session, between EDPO phases. The default is 255, - /// but decreasing it may reduce bus load at the expense of transfer time. + /// in an ETP session, between EDPO phases. The default is 16. + /// Note that the sending control function may choose to use a lower number of frames. /// @returns The number of data frames the stack will use when sending ETP messages between EDPOs - std::uint8_t get_max_number_of_etp_frames_per_edpo() const; + std::uint8_t get_number_of_packets_per_dpo_message() const; /// @brief Sets the max number of data frames the stack will send from each /// transport layer protocol, per update. The default is 255, @@ -73,13 +74,24 @@ namespace isobus /// @returns The max number of frames to use in transport protocols in each network manager update std::uint8_t get_max_number_of_network_manager_protocol_frames_per_update() const; + /// @brief Set the the number of packets per CTS message for TP sessions. The default + /// is 16. Note that the receiving control function may not support this limitation, or choose + /// to ignore it and use a different number of packets per CTS packet. + /// @param[in] numberPackets The number of packets per CTS packet for TP sessions. + void set_number_of_packets_per_cts_message(std::uint8_t numberPackets); + + /// @brief Get the the number of packets per CTS packet for TP sessions. + /// @returns The number of packets per CTS packet for TP sessions. + std::uint8_t get_number_of_packets_per_cts_message() const; + private: static constexpr std::uint8_t DEFAULT_BAM_PACKET_DELAY_TIME_MS = 50; ///< The default time between BAM frames, as defined by J1939 std::uint32_t maxNumberTransportProtocolSessions = 4; ///< The max number of TP sessions allowed std::uint32_t minimumTimeBetweenTransportProtocolBAMFrames = DEFAULT_BAM_PACKET_DELAY_TIME_MS; ///< The configurable time between BAM frames - std::uint8_t extendedTransportProtocolMaxNumberOfFramesPerEDPO = 0xFF; ///< Used to control throttling of ETP sessions. std::uint8_t networkManagerMaxFramesToSendPerUpdate = 0xFF; ///< Used to control the max number of transport layer frames added to the driver queue per network manager update + std::uint8_t numberOfPacketsPerDPOMessage = 16; ///< The number of packets per DPO message for ETP sessions + std::uint8_t numberOfPacketsPerCTSMessage = 16; ///< The number of packets per CTS message for TP sessions }; } // namespace isobus diff --git a/src/can_network_manager.cpp b/src/can_network_manager.cpp index 0a7ef28..23e13b5 100644 --- a/src/can_network_manager.cpp +++ b/src/can_network_manager.cpp @@ -31,10 +31,16 @@ namespace isobus void CANNetworkManager::initialize() { - receiveMessageList.clear(); + // Clear queues + while (!receivedMessageQueue.empty()) + { + get_next_can_message_from_rx_queue(); + } + while (!transmittedMessageQueue.empty()) + { + get_next_can_message_from_tx_queue(); + } initialized = true; - transportProtocol.initialize({}); - extendedTransportProtocol.initialize({}); } std::shared_ptr CANNetworkManager::get_control_function(std::uint8_t channelIndex, std::uint8_t address, CANLibBadge) const @@ -83,6 +89,11 @@ namespace isobus } } + EventDispatcher &CANNetworkManager::get_transmitted_message_event_dispatcher() + { + return messageTransmittedEventDispatcher; + } + std::shared_ptr CANNetworkManager::get_internal_control_function(std::shared_ptr controlFunction) { std::shared_ptr retVal = nullptr; @@ -132,25 +143,57 @@ namespace isobus ((parameterGroupNumber == static_cast(CANLibParameterGroupNumber::AddressClaim)) || (sourceControlFunction->get_address_valid()))) { - CANLibProtocol *currentProtocol; - - // See if any transport layer protocol can handle this message - for (std::uint32_t i = 0; i < CANLibProtocol::get_number_protocols(); i++) + std::unique_ptr messageData; + if (nullptr != frameChunkCallback) + { + messageData.reset(new CANMessageDataCallback(dataLength, frameChunkCallback, parentPointer)); + } + else { - if (CANLibProtocol::get_protocol(i, currentProtocol)) + messageData.reset(new CANMessageDataView(dataBuffer, dataLength)); + } + if (transportProtocols[sourceControlFunction->get_can_port()]->protocol_transmit_message(parameterGroupNumber, + messageData, + sourceControlFunction, + destinationControlFunction, + transmitCompleteCallback, + parentPointer)) + { + // Successfully sent via the transport protocol + retVal = true; + } + else if (extendedTransportProtocols[sourceControlFunction->get_can_port()]->protocol_transmit_message(parameterGroupNumber, + messageData, + sourceControlFunction, + destinationControlFunction, + transmitCompleteCallback, + parentPointer)) + { + // Successfully sent via the extended transport protocol + retVal = true; + } + else + { + //! @todo convert the other protocols to stop using the abstract protocollib class + CANLibProtocol *currentProtocol; + // See if any transport layer protocol can handle this message + for (std::uint32_t i = 0; i < CANLibProtocol::get_number_protocols(); i++) { - retVal = currentProtocol->protocol_transmit_message(parameterGroupNumber, - dataBuffer, - dataLength, - sourceControlFunction, - destinationControlFunction, - transmitCompleteCallback, - parentPointer, - frameChunkCallback); - - if (retVal) + if (CANLibProtocol::get_protocol(i, currentProtocol)) { - break; + retVal = currentProtocol->protocol_transmit_message(parameterGroupNumber, + dataBuffer, + dataLength, + sourceControlFunction, + destinationControlFunction, + transmitCompleteCallback, + parentPointer, + frameChunkCallback); + + if (retVal) + { + break; + } } } } @@ -162,11 +205,11 @@ namespace isobus if (nullptr == destinationControlFunction) { // Todo move binding of dest address to hardware layer - retVal = send_can_message_raw(sourceControlFunction->get_can_port(), sourceControlFunction->get_address(), 0xFF, parameterGroupNumber, priority, dataBuffer, dataLength); + retVal = send_can_message_raw(sourceControlFunction->get_can_port(), sourceControlFunction->get_address(), 0xFF, parameterGroupNumber, static_cast(priority), dataBuffer, dataLength); } else if (destinationControlFunction->get_address_valid()) { - retVal = send_can_message_raw(sourceControlFunction->get_can_port(), sourceControlFunction->get_address(), destinationControlFunction->get_address(), parameterGroupNumber, priority, dataBuffer, dataLength); + retVal = send_can_message_raw(sourceControlFunction->get_can_port(), sourceControlFunction->get_address(), destinationControlFunction->get_address(), parameterGroupNumber, static_cast(priority), dataBuffer, dataLength); } if ((retVal) && @@ -180,18 +223,6 @@ namespace isobus return retVal; } - void CANNetworkManager::receive_can_message(const CANMessage &message) - { - if (initialized) - { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(receiveMessageMutex); -#endif - - receiveMessageList.push_back(message); - } - } - void CANNetworkManager::update() { #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO @@ -206,11 +237,19 @@ namespace isobus update_new_partners(); process_rx_messages(); + process_tx_messages(); update_internal_cfs(); prune_inactive_control_functions(); + // Update transport protocols + for (std::uint32_t i = 0; i < CAN_PORT_MAXIMUM; i++) + { + transportProtocols[i]->update(); + extendedTransportProtocols[i]->update(); + } + for (std::size_t i = 0; i < CANLibProtocol::get_number_protocols(); i++) { CANLibProtocol *currentProtocol = nullptr; @@ -253,12 +292,12 @@ namespace isobus void receive_can_message_frame_from_hardware(const CANMessageFrame &rxFrame) { - CANNetworkManager::process_receive_can_message_frame(rxFrame); + CANNetworkManager::CANNetwork.process_receive_can_message_frame(rxFrame); } void on_transmit_can_message_frame_from_hardware(const CANMessageFrame &txFrame) { - CANNetworkManager::process_transmitted_can_message_frame(txFrame); + CANNetworkManager::CANNetwork.process_transmitted_can_message_frame(txFrame); } void periodic_update_from_hardware() @@ -268,24 +307,46 @@ namespace isobus void CANNetworkManager::process_receive_can_message_frame(const CANMessageFrame &rxFrame) { - CANMessage tempCANMessage(rxFrame.channel); - - CANNetworkManager::CANNetwork.update_control_functions(rxFrame); - - tempCANMessage.set_identifier(CANIdentifier(rxFrame.identifier)); + update_control_functions(rxFrame); - tempCANMessage.set_source_control_function(CANNetworkManager::CANNetwork.get_control_function(rxFrame.channel, tempCANMessage.get_identifier().get_source_address())); - tempCANMessage.set_destination_control_function(CANNetworkManager::CANNetwork.get_control_function(rxFrame.channel, tempCANMessage.get_identifier().get_destination_address())); - tempCANMessage.set_data(rxFrame.data, rxFrame.dataLength); + CANIdentifier identifier(rxFrame.identifier); + CANMessage message(CANMessage::Type::Receive, + identifier, + rxFrame.data, + rxFrame.dataLength, + get_control_function(rxFrame.channel, identifier.get_source_address()), + get_control_function(rxFrame.channel, identifier.get_destination_address()), + rxFrame.channel); - CANNetworkManager::CANNetwork.update_busload(rxFrame.channel, rxFrame.get_number_bits_in_message()); + update_busload(rxFrame.channel, rxFrame.get_number_bits_in_message()); - CANNetworkManager::CANNetwork.receive_can_message(tempCANMessage); + if (initialized) + { +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + std::lock_guard lock(receivedMessageQueueMutex); +#endif + receivedMessageQueue.push(std::move(message)); + } } void CANNetworkManager::process_transmitted_can_message_frame(const CANMessageFrame &txFrame) { - CANNetworkManager::CANNetwork.update_busload(txFrame.channel, txFrame.get_number_bits_in_message()); + update_busload(txFrame.channel, txFrame.get_number_bits_in_message()); + + CANIdentifier identifier(txFrame.identifier); + CANMessage message(CANMessage::Type::Transmit, + identifier, + txFrame.data, + txFrame.dataLength, + get_control_function(txFrame.channel, identifier.get_source_address()), + get_control_function(txFrame.channel, identifier.get_destination_address()), + txFrame.channel); + + if (initialized) + { + LOCK_GUARD(Mutex, transmittedMessageQueueMutex); + transmittedMessageQueue.push(std::move(message)); + } } void CANNetworkManager::on_control_function_destroyed(std::shared_ptr controlFunction, CANLibBadge) @@ -314,15 +375,18 @@ namespace isobus CANStackLogger::warn("[NM]: %s control function with address '%d' was at incorrect address '%d' in the lookup table prior to deletion.", controlFunction->get_type_string().c_str(), controlFunction->get_address(), i); } - if (initialized) - { - // The control function was active, replace it with an new external control function - controlFunctionTable[controlFunction->get_can_port()][controlFunction->address] = ControlFunction::create(controlFunction->get_NAME(), controlFunction->get_address(), controlFunction->get_can_port()); - } - else + if (controlFunction->get_address() < NULL_CAN_ADDRESS) { - // The network manager is not initialized yet, just remove the control function from the table - controlFunctionTable[controlFunction->get_can_port()][i] = nullptr; + if (initialized) + { + // The control function was active, replace it with an new external control function + controlFunctionTable[controlFunction->get_can_port()][controlFunction->address] = ControlFunction::create(controlFunction->get_NAME(), controlFunction->get_address(), controlFunction->get_can_port()); + } + else + { + // The network manager is not initialized yet, just remove the control function from the table + controlFunctionTable[controlFunction->get_can_port()][i] = nullptr; + } } } } @@ -382,6 +446,37 @@ namespace isobus return partneredControlFunctions; } + std::list> isobus::CANNetworkManager::get_control_functions(bool includingOffline) const + { + std::list> retVal; + + for (std::uint8_t channelIndex = 0; channelIndex < CAN_PORT_MAXIMUM; channelIndex++) + { + for (std::uint8_t address = 0; address < NULL_CAN_ADDRESS; address++) + { + if (nullptr != controlFunctionTable[channelIndex][address]) + { + retVal.push_back(controlFunctionTable[channelIndex][address]); + } + } + } + + if (includingOffline) + { + retVal.insert(retVal.end(), inactiveControlFunctions.begin(), inactiveControlFunctions.end()); + } + + return retVal; + } + + std::list> isobus::CANNetworkManager::get_active_transport_protocol_sessions(std::uint8_t canPortIndex) const + { + std::list> retVal; + retVal.insert(retVal.end(), transportProtocols[canPortIndex]->get_sessions().begin(), transportProtocols[canPortIndex]->get_sessions().end()); + retVal.insert(retVal.end(), extendedTransportProtocols[canPortIndex]->get_sessions().begin(), extendedTransportProtocols[canPortIndex]->get_sessions().end()); + return retVal; + } + FastPacketProtocol &CANNetworkManager::get_fast_packet_protocol() { return fastPacketProtocol; @@ -438,6 +533,28 @@ namespace isobus currentBusloadBitAccumulator.fill(0); lastAddressClaimRequestTimestamp_ms.fill(0); controlFunctionTable.fill({ nullptr }); + + auto send_frame_callback = [this](std::uint32_t parameterGroupNumber, + CANDataSpan data, + std::shared_ptr sourceControlFunction, + std::shared_ptr destinationControlFunction, + CANIdentifier::CANPriority priority) { return this->send_can_message(parameterGroupNumber, data.begin(), data.size(), sourceControlFunction, destinationControlFunction, priority); }; + + for (std::uint8_t i = 0; i < CAN_PORT_MAXIMUM; i++) + { + auto receive_message_callback = [this, i](const CANMessage &message) { + // TODO: hack port_index for now, once network manager isn't a singleton, this can be removed + CANMessage tempMessage(CANMessage::Type::Receive, + message.get_identifier(), + message.get_data(), + message.get_source_control_function(), + message.get_destination_control_function(), + i); + this->protocol_message_callback(message); + }; + transportProtocols[i].reset(new TransportProtocolManager(send_frame_callback, receive_message_callback, &configuration)); + extendedTransportProtocols[i].reset(new ExtendedTransportProtocolManager(send_frame_callback, receive_message_callback, &configuration)); + } } void CANNetworkManager::update_address_table(const CANMessage &message) @@ -802,19 +919,27 @@ namespace isobus CANMessage CANNetworkManager::get_next_can_message_from_rx_queue() { #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(receiveMessageMutex); + std::lock_guard lock(receivedMessageQueueMutex); #endif - CANMessage retVal = receiveMessageList.front(); - receiveMessageList.pop_front(); - return retVal; + if (!receivedMessageQueue.empty()) + { + CANMessage retVal = std::move(receivedMessageQueue.front()); + receivedMessageQueue.pop(); + return retVal; + } + return CANMessage::create_invalid_message(); } - std::size_t CANNetworkManager::get_number_can_messages_in_rx_queue() + CANMessage CANNetworkManager::get_next_can_message_from_tx_queue() { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(receiveMessageMutex); -#endif - return receiveMessageList.size(); + LOCK_GUARD(Mutex, transmittedMessageQueueMutex); + if (!transmittedMessageQueue.empty()) + { + CANMessage retVal = std::move(transmittedMessageQueue.front()); + transmittedMessageQueue.pop(); + return retVal; + } + return CANMessage::create_invalid_message(); } void CANNetworkManager::on_control_function_created(std::shared_ptr controlFunction) @@ -957,7 +1082,8 @@ namespace isobus void CANNetworkManager::process_rx_messages() { - while (0 != get_number_can_messages_in_rx_queue()) + // We may miss a message without locking the mutex when checking if empty, but that's okay. It will be picked up on the next iteration + while (!receivedMessageQueue.empty()) { CANMessage currentMessage = get_next_can_message_from_rx_queue(); @@ -965,6 +1091,8 @@ namespace isobus process_can_message_for_address_violations(currentMessage); // Update Special Callbacks, like protocols and non-cf specific ones + transportProtocols[currentMessage.get_can_port_index()]->process_message(currentMessage); + extendedTransportProtocols[currentMessage.get_can_port_index()]->process_message(currentMessage); process_protocol_pgn_callbacks(currentMessage); process_any_control_function_pgn_callbacks(currentMessage); @@ -973,6 +1101,18 @@ namespace isobus } } + void CANNetworkManager::process_tx_messages() + { + // We may miss a message without locking the mutex when checking if empty, but that's okay. It will be picked up on the next iteration + while (!transmittedMessageQueue.empty()) + { + CANMessage currentMessage = get_next_can_message_from_tx_queue(); + + // Update listen-only callbacks + messageTransmittedEventDispatcher.call(currentMessage); + } + } + void CANNetworkManager::prune_inactive_control_functions() { for (std::uint_fast8_t channelIndex = 0; channelIndex < CAN_PORT_MAXIMUM; channelIndex++) @@ -1021,6 +1161,7 @@ namespace isobus void CANNetworkManager::protocol_message_callback(const CANMessage &message) { process_can_message_for_global_and_partner_callbacks(message); + process_any_control_function_pgn_callbacks(message); process_can_message_for_commanded_address(message); } diff --git a/src/can_network_manager.hpp b/src/can_network_manager.hpp index 526beb4..92e1589 100644 --- a/src/can_network_manager.hpp +++ b/src/can_network_manager.hpp @@ -30,6 +30,7 @@ #include #include #include +#include #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO #include @@ -88,7 +89,13 @@ namespace isobus /// @param[in] parent A generic context variable that helps identify what object the callback was destined for void remove_any_control_function_parameter_group_number_callback(std::uint32_t parameterGroupNumber, CANLibCallback callback, void *parent); + /// @brief Returns the network manager's event dispatcher for notifying consumers whenever a + /// message is transmitted by our application + /// @returns An event dispatcher which can be used to get notified about transmitted messages + EventDispatcher &get_transmitted_message_event_dispatcher(); + /// @brief Returns an internal control function if the passed-in control function is an internal type + /// @param[in] controlFunction The control function to get the internal control function from /// @returns An internal control function casted from the passed in control function std::shared_ptr get_internal_control_function(std::shared_ptr controlFunction); @@ -106,6 +113,15 @@ namespace isobus /// If you don't specify a destination (or use nullptr) you message will be sent as a broadcast /// if it is valid to do so. /// You can also get a callback on success or failure of the transmit. + /// @param[in] parameterGroupNumber The PGN to use when sending the message + /// @param[in] dataBuffer A pointer to the data buffer to send from + /// @param[in] dataLength The size of the message to send + /// @param[in] sourceControlFunction The control function that is sending the message + /// @param[in] destinationControlFunction The control function that the message is destined for or nullptr if broadcast + /// @param[in] priority The CAN priority of the message being sent + /// @param[in] txCompleteCallback A callback to be called when the message is sent or fails to send + /// @param[in] parentPointer A generic context variable that helps identify what object the callback is destined for + /// @param[in] frameChunkCallback A callback which can be supplied to have the tack call you back to get chunks of the message as they are sent /// @returns `true` if the message was sent, otherwise `false` bool send_can_message(std::uint32_t parameterGroupNumber, const std::uint8_t *dataBuffer, @@ -117,22 +133,16 @@ namespace isobus void *parentPointer = nullptr, DataChunkCallback frameChunkCallback = nullptr); - /// @brief This is the main function used by the stack to receive CAN messages and add them to a queue. - /// @details This function is called by the stack itself when you call can_lib_process_rx_message. - /// @param[in] message The message to be received - void receive_can_message(const CANMessage &message); - /// @brief The main update function for the network manager. Updates all protocols. void update(); - /// @brief Process the CAN Rx queue + /// @brief Used to tell the network manager when frames are received on the bus. /// @param[in] rxFrame Frame to process - static void process_receive_can_message_frame(const CANMessageFrame &rxFrame); + void process_receive_can_message_frame(const CANMessageFrame &rxFrame); - /// @brief Used to tell the network manager when frames are emitted on the bus, so that they can be - /// added to the internal bus load calculations. + /// @brief Used to tell the network manager when frames are emitted on the bus. /// @param[in] txFrame The frame that was just emitted onto the bus - static void process_transmitted_can_message_frame(const CANMessageFrame &txFrame); + void process_transmitted_can_message_frame(const CANMessageFrame &txFrame); /// @brief Informs the network manager that a control function object has been destroyed, so that it can be purged from the network manager /// @param[in] controlFunction The control function that was destroyed @@ -167,6 +177,17 @@ namespace isobus /// @returns A list of all the partnered control functions const std::list> &get_partnered_control_functions() const; + /// @brief Gets all the control functions that are known to the network manager + /// @param[in] includingOffline If true, all control functions are returned, otherwise only online control functions are returned + /// @returns A list of all the control functions + std::list> get_control_functions(bool includingOffline) const; + + /// @brief Gets all the active transport protocol sessions that are currently active + /// @note The list returns pointers to the transport protocol sessions, but they can disappear at any time + /// @param[in] canPortIndex The CAN channel index to get the transport protocol sessions for + /// @returns A list of all the active transport protocol sessions + std::list> get_active_transport_protocol_sessions(std::uint8_t canPortIndex) const; + /// @brief Returns the class instance of the NMEA2k fast packet protocol. /// Use this to register for FP multipacket messages /// @returns The class instance of the NMEA2k fast packet protocol. @@ -189,7 +210,7 @@ namespace isobus friend class DiagnosticProtocol; ///< Allows the diagnostic protocol to access the protected functions on the network manager friend class ParameterGroupNumberRequestProtocol; ///< Allows the PGN request protocol to access the network manager protected functions friend class FastPacketProtocol; ///< Allows the FP protocol to access the network manager protected functions - friend class CANLibProtocol; + friend class CANLibProtocol; ///< Allows the CANLib protocol base class functions to access the network manager protected functions /// @brief Adds a PGN callback for a protocol class /// @param[in] parameterGroupNumber The PGN to register for @@ -278,14 +299,15 @@ namespace isobus /// @returns A control function matching the address and CAN port passed in std::shared_ptr get_control_function(std::uint8_t channelIndex, std::uint8_t address) const; - /// @brief Gets a message from the Rx Queue. - /// @note This will only ever get an 8 byte message. Long messages are handled elsewhere. - /// @returns The can message that was at the front of the buffer + /// @brief Get the next CAN message from the received message queue, and remove it from the queue. + /// @note This will only ever get an 8 byte message because they are directly translated from CAN frames. + /// @returns The message that was at the front of the queue, or an invalid message if the queue is empty CANMessage get_next_can_message_from_rx_queue(); - /// @brief Returns the number of messages in the rx queue that need to be processed - /// @returns The number of messages in the rx queue that need to be processed - std::size_t get_number_can_messages_in_rx_queue(); + /// @brief Get the next CAN message from the received message queue, and remove it from the queue + /// @note This will only ever get an 8 byte message because they are directly translated from CAN frames. + /// @returns The message that was at the front of the queue, or an invalid message if the queue is empty + CANMessage get_next_can_message_from_tx_queue(); /// @brief Informs the network manager that a control function object has been created /// @param[in] controlFunction The control function that was created @@ -323,9 +345,12 @@ namespace isobus /// @param[in] message The message to process void process_can_message_for_commanded_address(const CANMessage &message); - /// @brief Processes the internal receive message queue + /// @brief Processes the internal received message queue void process_rx_messages(); + /// @brief Processes the internal transmitted message queue + void process_tx_messages(); + /// @brief Checks to see if any control function didn't claim during a round of /// address claiming and removes it if needed. void prune_inactive_control_functions(); @@ -356,9 +381,9 @@ namespace isobus static constexpr std::uint32_t BUSLOAD_UPDATE_FREQUENCY_MS = 100; ///< Bus load bit accumulation happens over a 100ms window CANNetworkConfiguration configuration; ///< The configuration for this network manager - ExtendedTransportProtocolManager extendedTransportProtocol; ///< Static instance of the protocol manager + std::array, CAN_PORT_MAXIMUM> transportProtocols; ///< One instance of the transport protocol manager for each channel + std::array, CAN_PORT_MAXIMUM> extendedTransportProtocols; ///< One instance of the extended transport protocol manager for each channel FastPacketProtocol fastPacketProtocol; ///< Instance of the fast packet protocol - TransportProtocolManager transportProtocol; ///< Static instance of the transport protocol manager std::array, CAN_PORT_MAXIMUM> busloadMessageBitsHistory; ///< Stores the approximate number of bits processed on each channel over multiple previous time windows std::array currentBusloadBitAccumulator; ///< Accumulates the approximate number of bits processed on each channel during the current time window @@ -370,18 +395,21 @@ namespace isobus std::list> partneredControlFunctions; ///< A list of the partnered control functions std::list protocolPGNCallbacks; ///< A list of PGN callback registered by CAN protocols - std::list receiveMessageList; ///< A queue of Rx messages to process + std::queue receivedMessageQueue; ///< A queue of received messages to process + std::queue transmittedMessageQueue; ///< A queue of transmitted messages to process (already sent, so changes to the message won't affect the bus) std::list controlFunctionStateCallbacks; ///< List of all control function state callbacks std::vector globalParameterGroupNumberCallbacks; ///< A list of all global PGN callbacks std::vector anyControlFunctionParameterGroupNumberCallbacks; ///< A list of all global PGN callbacks - EventDispatcher> addressViolationEventDispatcher; // An event dispatcher for notifying consumers about address violations + EventDispatcher messageTransmittedEventDispatcher; ///< An event dispatcher for notifying consumers about transmitted messages by our application + EventDispatcher> addressViolationEventDispatcher; ///< An event dispatcher for notifying consumers about address violations #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::mutex receiveMessageMutex; ///< A mutex for receive messages thread safety + std::mutex receivedMessageQueueMutex; ///< A mutex for receive messages thread safety std::mutex protocolPGNCallbacksMutex; ///< A mutex for PGN callback thread safety std::mutex anyControlFunctionCallbacksMutex; ///< Mutex to protect the "any CF" callbacks std::mutex busloadUpdateMutex; ///< A mutex that protects the busload metrics since we calculate it on our own thread std::mutex controlFunctionStatusCallbacksMutex; ///< A Mutex that protects access to the control function status callback list #endif + Mutex transmittedMessageQueueMutex; ///< A mutex for protecting the transmitted message queue std::uint32_t busloadUpdateTimestamp_ms = 0; ///< Tracks a time window for determining approximate busload std::uint32_t updateTimestamp_ms = 0; ///< Keeps track of the last time the CAN stack was update in milliseconds bool initialized = false; ///< True if the network manager has been initialized by the update function diff --git a/src/can_partnered_control_function.hpp b/src/can_partnered_control_function.hpp index 536873a..e991b96 100644 --- a/src/can_partnered_control_function.hpp +++ b/src/can_partnered_control_function.hpp @@ -41,6 +41,7 @@ namespace isobus /// @brief The factory function to construct a partnered control function /// @param[in] CANPort The CAN channel associated with this control function definition /// @param[in] NAMEFilters A list of filters that describe the identity of the CF based on NAME components + /// @returns A shared pointer to a PartneredControlFunction object created with the parameters passed in static std::shared_ptr create(std::uint8_t CANPort, const std::vector NAMEFilters); /// @brief the constructor for a PartneredControlFunction, which is called by the factory function diff --git a/src/can_transport_protocol.cpp b/src/can_transport_protocol.cpp index 86fcf0d..e34e01d 100644 --- a/src/can_transport_protocol.cpp +++ b/src/can_transport_protocol.cpp @@ -4,867 +4,995 @@ /// @brief A protocol that handles the ISO11783/J1939 transport protocol. /// It handles both the broadcast version (BAM) and and the connection mode version. /// @author Adrian Del Grosso +/// @author Daan Steenbergen /// -/// @copyright 2022 Adrian Del Grosso +/// @copyright 2023 The Open-Agriculture Developers //================================================================================================ #include "can_transport_protocol.hpp" #include "can_general_parameter_group_numbers.hpp" -#include "can_network_configuration.hpp" -#include "can_network_manager.hpp" +#include "can_internal_control_function.hpp" +#include "can_message.hpp" #include "can_stack_logger.hpp" #include "system_timing.hpp" #include "to_string.hpp" #include +#include namespace isobus { - TransportProtocolManager::TransportProtocolSession::TransportProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex) : - sessionMessage(canPortIndex), - sessionDirection(sessionDirection) + TransportProtocolManager::TransportProtocolSession::TransportProtocolSession(Direction direction, std::unique_ptr data, std::uint32_t parameterGroupNumber, std::uint16_t totalMessageSize, std::uint8_t clearToSendPacketMax, std::shared_ptr source, std::shared_ptr destination, TransmitCompleteCallback sessionCompleteCallback, void *parentPointer) : + TransportProtocolSessionBase(direction, std::move(data), parameterGroupNumber, totalMessageSize, source, destination, sessionCompleteCallback, parentPointer), + clearToSendPacketCountMax(clearToSendPacketMax) { } - bool TransportProtocolManager::TransportProtocolSession::operator==(const TransportProtocolSession &obj) + TransportProtocolManager::StateMachineState TransportProtocolManager::TransportProtocolSession::get_state() const { - return ((sessionMessage.get_source_control_function() == obj.sessionMessage.get_source_control_function()) && - (sessionMessage.get_destination_control_function() == obj.sessionMessage.get_destination_control_function()) && - (sessionMessage.get_identifier().get_parameter_group_number() == obj.sessionMessage.get_identifier().get_parameter_group_number())); + return state; } - std::uint32_t TransportProtocolManager::TransportProtocolSession::get_message_data_length() const + std::uint16_t TransportProtocolManager::TransportProtocolSession::get_message_length() const { - if (nullptr != frameChunkCallback) - { - return frameChunkCallbackMessageLength; - } - return sessionMessage.get_data_length(); + // We know that this session can only be used to transfer 1785 bytes of data, so we can safely cast to a uint16_t + return static_cast(TransportProtocolSessionBase::get_message_length()); } - TransportProtocolManager::~TransportProtocolManager() + bool TransportProtocolManager::TransportProtocolSession::is_broadcast() const { - // No need to clean up, as this object is a member of the network manager - // so its callbacks will be cleared at destruction time + return (nullptr == get_destination()); } - void TransportProtocolManager::initialize(CANLibBadge) + std::uint32_t TransportProtocolManager::TransportProtocolSession::get_total_bytes_transferred() const { - if (!initialized) + uint32_t transferred = get_last_packet_number() * PROTOCOL_BYTES_PER_FRAME; + if (transferred > get_message_length()) { - initialized = true; - CANNetworkManager::CANNetwork.add_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), process_message, this); - CANNetworkManager::CANNetwork.add_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::TransportProtocolData), process_message, this); + transferred = get_message_length(); } + return transferred; } - void TransportProtocolManager::process_message(const CANMessage &message) + void TransportProtocolManager::TransportProtocolSession::set_state(StateMachineState value) { - if ((nullptr != message.get_source_control_function()) && - ((nullptr == message.get_destination_control_function()) || - (nullptr != CANNetworkManager::CANNetwork.get_internal_control_function(message.get_destination_control_function())))) - { - switch (message.get_identifier().get_parameter_group_number()) - { - case static_cast(CANLibParameterGroupNumber::TransportProtocolCommand): - { - TransportProtocolSession *session; - const auto &data = message.get_data(); - const std::uint32_t pgn = (static_cast(data[5]) | (static_cast(data[6]) << 8) | (static_cast(data[7]) << 16)); - switch (data[0]) - { - case BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR: - { - if (CAN_DATA_LENGTH == message.get_data_length()) - { - if ((nullptr == message.get_destination_control_function()) && - (activeSessions.size() < CANNetworkManager::CANNetwork.get_configuration().get_max_number_transport_protocol_sessions()) && - (!get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn))) - { - TransportProtocolSession *newSession = new TransportProtocolSession(TransportProtocolSession::Direction::Receive, message.get_can_port_index()); - CANIdentifier tempIdentifierData(CANIdentifier::Type::Extended, pgn, CANIdentifier::CANPriority::PriorityLowest7, BROADCAST_CAN_ADDRESS, message.get_source_control_function()->get_address()); - newSession->sessionMessage.set_data_size(static_cast(data[1]) | static_cast(data[2] << 8)); - newSession->sessionMessage.set_source_control_function(message.get_source_control_function()); - newSession->sessionMessage.set_destination_control_function(nullptr); - newSession->packetCount = data[3]; - newSession->sessionMessage.set_identifier(tempIdentifierData); - newSession->state = StateMachineState::RxDataSession; - newSession->timestamp_ms = SystemTiming::get_timestamp_ms(); - activeSessions.push_back(newSession); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, - "[TP]: New Rx BAM Session. Source: " + - isobus::to_string(static_cast(newSession->sessionMessage.get_source_control_function()->get_address()))); - } - else - { - // Don't send an abort, they're probably expecting a CTS so it'll timeout - // Or maybe if we already had a session they sent a second BAM? Also bad - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Can't Create an Rx BAM session"); - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Bad BAM Message Length"); - } - } - break; + state = value; + update_timestamp(); + } - case REQUEST_TO_SEND_MULTIPLEXOR: - { - if (CAN_DATA_LENGTH == message.get_data_length()) - { - if ((nullptr != message.get_destination_control_function()) && - (activeSessions.size() < CANNetworkManager::CANNetwork.get_configuration().get_max_number_transport_protocol_sessions()) && - (!get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn))) - { - TransportProtocolSession *newSession = new TransportProtocolSession(TransportProtocolSession::Direction::Receive, message.get_can_port_index()); - CANIdentifier tempIdentifierData(CANIdentifier::Type::Extended, pgn, CANIdentifier::CANPriority::PriorityLowest7, message.get_destination_control_function()->get_address(), message.get_source_control_function()->get_address()); - newSession->sessionMessage.set_data_size(static_cast(data[1]) | static_cast(data[2] << 8)); - newSession->sessionMessage.set_source_control_function(message.get_source_control_function()); - newSession->sessionMessage.set_destination_control_function(message.get_destination_control_function()); - newSession->packetCount = data[3]; - newSession->clearToSendPacketMax = data[4]; - newSession->sessionMessage.set_identifier(tempIdentifierData); - newSession->state = StateMachineState::ClearToSend; - newSession->timestamp_ms = SystemTiming::get_timestamp_ms(); - activeSessions.push_back(newSession); - } - else if ((get_session(session, message.get_source_control_function(), message.get_destination_control_function(), pgn)) && - (nullptr != message.get_destination_control_function()) && - (ControlFunction::Type::Internal == message.get_destination_control_function()->get_type())) - { - abort_session(pgn, ConnectionAbortReason::AlreadyInCMSession, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, RTS when already in CM session"); - } - else if ((activeSessions.size() >= CANNetworkManager::CANNetwork.get_configuration().get_max_number_transport_protocol_sessions()) && - (nullptr != message.get_destination_control_function()) && - (ControlFunction::Type::Internal == message.get_destination_control_function()->get_type())) - { - abort_session(pgn, ConnectionAbortReason::SystemResourcesNeeded, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, No Sessions Available"); - } - } - else - { - // Bad RTS message length. Can't really abort? Not sure what the PGN is if length < 8 - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Received Bad Message Length for an RTS"); - } - } - break; + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_cts_number_of_packets_remaining() const + { + std::uint8_t packetsSinceCTS = get_last_packet_number() - lastAcknowledgedPacketNumber; + return clearToSendPacketCount - packetsSinceCTS; + } - case CLEAR_TO_SEND_MULTIPLEXOR: - { - // Can't happen when doing a BAM session, make sure the session type is correct - if ((CAN_DATA_LENGTH == message.get_data_length()) && - (nullptr != message.get_destination_control_function()) && - (nullptr != message.get_source_control_function())) - { - const std::uint8_t packetsToBeSent = data[1]; - - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - if (StateMachineState::WaitForClearToSend == session->state) - { - session->packetCount = packetsToBeSent; - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - // If 0 was sent as the packet number, they want us to wait. - // Just sit here in this state until we get a non-zero packet count - if (0 != packetsToBeSent) - { - session->lastPacketNumber = 0; - session->state = StateMachineState::TxDataSession; - } - } - else - { - // The session exists, but we're probably already in the TxDataSession state. Need to abort - // In the case of Rx'ing a CTS, we're the source in the session - abort_session(pgn, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, CTS while in data session, PGN: " + isobus::to_string(pgn)); - } - } - else - { - // We got a CTS but no session exists. Aborting clears up the situation faster than waiting for them to timeout - // In the case of Rx'ing a CTS, we're the source in the session - abort_session(pgn, ConnectionAbortReason::AnyOtherError, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, CTS With no matching session, PGN: " + isobus::to_string(pgn)); - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Received an Invalid CTS"); - } - } - break; + void TransportProtocolManager::TransportProtocolSession::set_cts_number_of_packets(std::uint8_t value) + { + clearToSendPacketCount = value; + update_timestamp(); + } - case END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR: - { - // Can't happen when doing a BAM session, make sure the session type is correct - if ((CAN_DATA_LENGTH == message.get_data_length()) && - (nullptr != message.get_destination_control_function()) && - (nullptr != message.get_source_control_function())) - { - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - if (StateMachineState::WaitForEndOfMessageAcknowledge == session->state) - { - // We completed our Tx session! - session->state = StateMachineState::None; - close_session(session, true); - } - else - { - abort_session(pgn, ConnectionAbortReason::AnyOtherError, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - close_session(session, false); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, received EOM in wrong session state, PGN: " + isobus::to_string(pgn)); - } - } - else - { - abort_session(pgn, ConnectionAbortReason::AnyOtherError, std::static_pointer_cast(message.get_destination_control_function()), message.get_source_control_function()); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Sent abort, received EOM without matching session, PGN: " + isobus::to_string(pgn)); - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Bad EOM received"); - } - } - break; + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_cts_number_of_packets() const + { + return clearToSendPacketCount; + } - case CONNECTION_ABORT_MULTIPLEXOR: - { - if (get_session(session, message.get_destination_control_function(), message.get_source_control_function(), pgn)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Received an abort for an session with PGN: " + isobus::to_string(pgn)); - close_session(session, false); - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Received an abort with no matching session with PGN: " + isobus::to_string(pgn)); - } - } - break; + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_rts_number_of_packet_limit() const + { + return clearToSendPacketCountMax; + } - default: - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Bad Mux in Transport Protocol Command"); - } - break; - } - } - break; + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_last_sequence_number() const + { + return lastSequenceNumber; + } - case static_cast(CANLibParameterGroupNumber::TransportProtocolData): - { - TransportProtocolSession *tempSession = nullptr; + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_last_packet_number() const + { + return lastSequenceNumber; + } - if ((CAN_DATA_LENGTH == message.get_data_length()) && - (get_session(tempSession, message.get_source_control_function(), message.get_destination_control_function())) && - (StateMachineState::RxDataSession == tempSession->state)) - { - // Check for valid sequence number - if (message.get_data()[SEQUENCE_NUMBER_DATA_INDEX] == (tempSession->lastPacketNumber + 1)) - { - for (std::uint8_t i = SEQUENCE_NUMBER_DATA_INDEX; (i < PROTOCOL_BYTES_PER_FRAME) && (static_cast((PROTOCOL_BYTES_PER_FRAME * tempSession->lastPacketNumber) + i) < tempSession->get_message_data_length()); i++) - { - std::uint16_t currentDataIndex = (PROTOCOL_BYTES_PER_FRAME * tempSession->lastPacketNumber) + i; - tempSession->sessionMessage.set_data(message.get_data()[1 + SEQUENCE_NUMBER_DATA_INDEX + i], currentDataIndex); - } - tempSession->lastPacketNumber++; - tempSession->processedPacketsThisSession++; - if ((tempSession->lastPacketNumber * PROTOCOL_BYTES_PER_FRAME) >= tempSession->get_message_data_length()) - { - // Send EOM Ack for CM sessions only - if (nullptr != tempSession->sessionMessage.get_destination_control_function()) - { - send_end_of_session_acknowledgement(tempSession); - } - CANNetworkManager::CANNetwork.process_any_control_function_pgn_callbacks(tempSession->sessionMessage); - CANNetworkManager::CANNetwork.protocol_message_callback(tempSession->sessionMessage); - close_session(tempSession, true); - } - tempSession->timestamp_ms = SystemTiming::get_timestamp_ms(); - } - else if (message.get_data()[SEQUENCE_NUMBER_DATA_INDEX] == (tempSession->lastPacketNumber)) - { - // Sequence number is duplicate of the last one - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Aborting session due to duplciate sequence number"); - abort_session(tempSession, ConnectionAbortReason::DuplicateSequenceNumber); - close_session(tempSession, false); - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Aborting session due to bad sequence number"); - abort_session(tempSession, ConnectionAbortReason::BadSequenceNumber); - close_session(tempSession, false); - } - } - else - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Invalid BAM TP Data Received"); - if (get_session(tempSession, message.get_source_control_function(), message.get_destination_control_function())) - { - // If a session matches and ther was an error, get rid of the session - close_session(tempSession, false); - } - } - } - break; + void TransportProtocolManager::TransportProtocolSession::set_last_sequency_number(std::uint8_t value) + { + lastSequenceNumber = value; + update_timestamp(); + } - default: - { - // This is not a runtime error, should never happen. - // Bad PGN passed to protocol. Check PGN registrations. - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Received an unexpected PGN"); - } - break; - } - } + void TransportProtocolManager::TransportProtocolSession::set_acknowledged_packet_number(std::uint8_t value) + { + lastAcknowledgedPacketNumber = value; + update_timestamp(); + } + + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_number_of_remaining_packets() const + { + return get_total_number_of_packets() - get_last_packet_number(); } - void TransportProtocolManager::process_message(const CANMessage &message, void *parent) + std::uint8_t TransportProtocolManager::TransportProtocolSession::get_total_number_of_packets() const { - if (nullptr != parent) + auto totalNumberOfPackets = static_cast(get_message_length() / PROTOCOL_BYTES_PER_FRAME); + if ((get_message_length() % PROTOCOL_BYTES_PER_FRAME) > 0) { - reinterpret_cast(parent)->process_message(message); + totalNumberOfPackets++; } + return totalNumberOfPackets; } - bool TransportProtocolManager::protocol_transmit_message(std::uint32_t parameterGroupNumber, - const std::uint8_t *dataBuffer, - std::uint32_t messageLength, - std::shared_ptr source, - std::shared_ptr destination, - TransmitCompleteCallback sessionCompleteCallback, - void *parentPointer, - DataChunkCallback frameChunkCallback) + TransportProtocolManager::TransportProtocolManager(const CANMessageFrameCallback &sendCANFrameCallback, + const CANMessageCallback &canMessageReceivedCallback, + const CANNetworkConfiguration *configuration) : + sendCANFrameCallback(sendCANFrameCallback), + canMessageReceivedCallback(canMessageReceivedCallback), + configuration(configuration) { - TransportProtocolSession *session; - bool retVal = false; + } - if ((messageLength <= MAX_PROTOCOL_DATA_LENGTH) && - (messageLength > CAN_DATA_LENGTH) && - ((nullptr != dataBuffer) || - (nullptr != frameChunkCallback)) && - (nullptr != source) && - (true == source->get_address_valid()) && - ((nullptr == destination) || - (destination->get_address_valid())) && - (!get_session(session, source, destination, parameterGroupNumber)) && - ((nullptr != destination) || - ((nullptr == destination) && - (!get_session(session, source, destination))))) + void TransportProtocolManager::process_broadcast_announce_message(const std::shared_ptr source, + std::uint32_t parameterGroupNumber, + std::uint16_t totalMessageSize, + std::uint8_t totalNumberOfPackets) + { + // The standard defines that we may not send aborts for messages with a global destination, we can only ignore them if we need to + if (activeSessions.size() >= configuration->get_max_number_transport_protocol_sessions()) { - TransportProtocolSession *newSession = new TransportProtocolSession(TransportProtocolSession::Direction::Transmit, - source->get_can_port()); - std::uint8_t destinationAddress; - - if (dataBuffer != nullptr) - { - newSession->sessionMessage.set_data(dataBuffer, messageLength); - } - else - { - newSession->frameChunkCallback = frameChunkCallback; - newSession->frameChunkCallbackMessageLength = messageLength; - } - newSession->sessionMessage.set_source_control_function(source); - newSession->sessionMessage.set_destination_control_function(destination); - newSession->packetCount = (messageLength / PROTOCOL_BYTES_PER_FRAME); - newSession->lastPacketNumber = 0; - newSession->processedPacketsThisSession = 0; - newSession->sessionCompleteCallback = sessionCompleteCallback; - newSession->parent = parentPointer; - if (0 != (messageLength % PROTOCOL_BYTES_PER_FRAME)) + // TODO: consider using maximum memory instead of maximum number of sessions + CANStackLogger::warn("[TP]: Ignoring Broadcast Announcement Message (BAM) for 0x%05X, configured maximum number of sessions reached.", parameterGroupNumber); + } + else if (totalMessageSize > MAX_PROTOCOL_DATA_LENGTH) + { + CANStackLogger::warn("[TP]: Ignoring Broadcast Announcement Message (BAM) for 0x%05X, message size (%hu) is greater than the maximum (%hu).", parameterGroupNumber, totalMessageSize, MAX_PROTOCOL_DATA_LENGTH); + } + else + { + auto oldSession = get_session(source, nullptr); + if (nullptr != oldSession) { - newSession->packetCount++; + CANStackLogger::warn("[TP]: Received Broadcast Announcement Message (BAM) while a session already existed for this source (%hu), overwriting for 0x%05X...", source->get_address(), parameterGroupNumber); + close_session(oldSession, false); } - if (nullptr != destination) + auto newSession = std::make_shared(TransportProtocolSession::Direction::Receive, + std::unique_ptr(new CANMessageDataVector(totalMessageSize)), + parameterGroupNumber, + totalMessageSize, + 0xFF, // Arbitrary - unused for broadcast + source, + nullptr, // Global destination + nullptr, // No callback + nullptr); + + if (newSession->get_total_number_of_packets() != totalNumberOfPackets) { - // CM Message - destinationAddress = destination->get_address(); - set_state(newSession, StateMachineState::RequestToSend); + CANStackLogger::warn("[TP]: Received Broadcast Announcement Message (BAM) for 0x%05X with a bad number of packets, aborting...", parameterGroupNumber); } else { - // BAM message - destinationAddress = BROADCAST_CAN_ADDRESS; - set_state(newSession, StateMachineState::BroadcastAnnounce); + newSession->set_state(StateMachineState::WaitForDataTransferPacket); + activeSessions.push_back(newSession); + update_state_machine(newSession); + CANStackLogger::debug("[TP]: New rx broadcast message session for 0x%05X. Source: %hu", parameterGroupNumber, source->get_address()); } - - CANIdentifier messageVirtualID(CANIdentifier::Type::Extended, - parameterGroupNumber, - CANIdentifier::CANPriority::PriorityDefault6, - destinationAddress, - source->get_address()); - - newSession->sessionMessage.set_identifier(messageVirtualID); - - activeSessions.push_back(newSession); - retVal = true; } - return retVal; } - void TransportProtocolManager::update(CANLibBadge) + void TransportProtocolManager::process_request_to_send(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint16_t totalMessageSize, + std::uint8_t totalNumberOfPackets, + std::uint8_t clearToSendPacketMax) { - for (auto i : activeSessions) + if (activeSessions.size() >= configuration->get_max_number_transport_protocol_sessions()) { - update_state_machine(i); + // TODO: consider using maximum memory instead of maximum number of sessions + CANStackLogger::warn("[TP]: Replying with abort to Request To Send (RTS) for 0x%05X, configured maximum number of sessions reached.", parameterGroupNumber); + send_abort(std::static_pointer_cast(destination), source, parameterGroupNumber, ConnectionAbortReason::AlreadyInCMSession); } - } + else + { + auto oldSession = get_session(source, destination); + if (nullptr != oldSession) + { + if (oldSession->get_parameter_group_number() != parameterGroupNumber) + { + CANStackLogger::error("[TP]: Received Request To Send (RTS) while a session already existed for this source and destination, aborting for 0x%05X...", parameterGroupNumber); + abort_session(oldSession, ConnectionAbortReason::AlreadyInCMSession); + } + else + { + CANStackLogger::warn("[TP]: Received Request To Send (RTS) while a session already existed for this source and destination and parameterGroupNumber, overwriting for 0x%05X...", parameterGroupNumber); + close_session(oldSession, false); + } + } - bool TransportProtocolManager::abort_session(TransportProtocolSession *session, ConnectionAbortReason reason) - { - bool retVal = false; + auto data = std::unique_ptr(new CANMessageDataVector(totalMessageSize)); - if (nullptr != session) - { - std::shared_ptr myControlFunction; - std::shared_ptr partnerControlFunction; - std::array data; - std::uint32_t pgn = session->sessionMessage.get_identifier().get_parameter_group_number(); + if (clearToSendPacketMax > configuration->get_number_of_packets_per_cts_message()) + { + CANStackLogger::debug("[TP]: Received Request To Send (RTS) with a CTS packet count of %hu, which is greater than the configured maximum of %hu, using the configured maximum instead.", clearToSendPacketMax, configuration->get_number_of_packets_per_cts_message()); + clearToSendPacketMax = configuration->get_number_of_packets_per_cts_message(); + } - if (TransportProtocolSession::Direction::Transmit == session->sessionDirection) + auto newSession = std::make_shared(TransportProtocolSession::Direction::Receive, + std::unique_ptr(new CANMessageDataVector(totalMessageSize)), + parameterGroupNumber, + totalMessageSize, + clearToSendPacketMax, + source, + destination, + nullptr, // No callback + nullptr); + + if (newSession->get_total_number_of_packets() != totalNumberOfPackets) { - myControlFunction = CANNetworkManager::CANNetwork.get_internal_control_function(session->sessionMessage.get_source_control_function()); - partnerControlFunction = session->sessionMessage.get_destination_control_function(); + CANStackLogger::error("[TP]: Received Request To Send (RTS) for 0x%05X with a bad number of packets, aborting...", parameterGroupNumber); + abort_session(newSession, ConnectionAbortReason::AnyOtherError); } else { - myControlFunction = CANNetworkManager::CANNetwork.get_internal_control_function(session->sessionMessage.get_destination_control_function()); - partnerControlFunction = session->sessionMessage.get_source_control_function(); - } - - data[0] = CONNECTION_ABORT_MULTIPLEXOR; - data[1] = static_cast(reason); - data[2] = 0xFF; - data[3] = 0xFF; - data[4] = 0xFF; - data[5] = static_cast(pgn & 0xFF); - data[6] = static_cast((pgn >> 8) & 0xFF); - data[7] = static_cast((pgn >> 16) & 0xFF); - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - data.data(), - 8, - myControlFunction, - partnerControlFunction, - CANIdentifier::CANPriority::PriorityDefault6); + newSession->set_state(StateMachineState::SendClearToSend); + activeSessions.push_back(newSession); + CANStackLogger::debug("[TP]: New rx session for 0x%05X. Source: %hu, destination: %hu", parameterGroupNumber, source->get_address(), destination->get_address()); + update_state_machine(newSession); + } } - return retVal; } - bool TransportProtocolManager::abort_session(std::uint32_t parameterGroupNumber, ConnectionAbortReason reason, std::shared_ptr source, std::shared_ptr destination) + void TransportProtocolManager::process_clear_to_send(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + std::uint8_t packetsToBeSent, + std::uint8_t nextPacketNumber) { - std::array data; + auto session = get_session(destination, source); + if (nullptr != session) + { + if (session->get_parameter_group_number() != parameterGroupNumber) + { + CANStackLogger::error("[TP]: Received a Clear To Send (CTS) message for 0x%05X while a session already existed for this source and destination, sending abort for both...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + send_abort(std::static_pointer_cast(destination), source, parameterGroupNumber, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + } + else if (nextPacketNumber > session->get_total_number_of_packets()) + { + CANStackLogger::error("[TP]: Received a Clear To Send (CTS) message for 0x%05X with a bad sequence number, aborting...", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::BadSequenceNumber); + } + else if (StateMachineState::WaitForClearToSend != session->state) + { + // The session exists, but we're not in the right state to receive a CTS, so we must abort + CANStackLogger::warn("[TP]: Received a Clear To Send (CTS) message for 0x%05X, but not expecting one, aborting session.", parameterGroupNumber); + abort_session(session, ConnectionAbortReason::ClearToSendReceivedWhileTransferInProgress); + } + else + { + session->set_acknowledged_packet_number(nextPacketNumber - 1); + session->set_cts_number_of_packets(packetsToBeSent); - data[0] = CONNECTION_ABORT_MULTIPLEXOR; - data[1] = static_cast(reason); - data[2] = 0xFF; - data[3] = 0xFF; - data[4] = 0xFF; - data[5] = static_cast(parameterGroupNumber & 0xFF); - data[6] = static_cast((parameterGroupNumber >> 8) & 0xFF); - data[7] = static_cast((parameterGroupNumber >> 16) & 0xFF); - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - data.data(), - 8, - source, - destination, - CANIdentifier::CANPriority::PriorityDefault6); + // If 0 was sent as the packet number, they want us to wait. + // Just sit here in this state until we get a non-zero packet count + if (0 != packetsToBeSent) + { + session->set_state(StateMachineState::SendDataTransferPackets); + } + } + } + else + { + // We got a CTS but no session exists, by the standard we must ignore it + CANStackLogger::warn("[TP]: Received Clear To Send (CTS) for 0x%05X while no session existed for this source and destination, ignoring...", parameterGroupNumber); + } } - void TransportProtocolManager::close_session(TransportProtocolSession *session, bool successfull) + void TransportProtocolManager::process_end_of_session_acknowledgement(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber) { + auto session = get_session(destination, source); if (nullptr != session) { - process_session_complete_callback(session, successfull); - auto sessionLocation = std::find(activeSessions.begin(), activeSessions.end(), session); - if (activeSessions.end() != sessionLocation) + if (StateMachineState::WaitForEndOfMessageAcknowledge == session->state) { - activeSessions.erase(sessionLocation); - delete session; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[TP]: Session Closed"); + session->state = StateMachineState::None; + close_session(session, true); + CANStackLogger::debug("[TP]: Completed tx session for 0x%05X from %hu", parameterGroupNumber, source->get_address()); + } + else + { + // The session exists, but we're not in the right state to receive an EOM, by the standard we must ignore it + CANStackLogger::warn("[TP]: Received an End Of Message Acknowledgement message for 0x%05X, but not expecting one, ignoring.", parameterGroupNumber); } } - } - - void TransportProtocolManager::process_session_complete_callback(TransportProtocolSession *session, bool success) - { - if ((nullptr != session) && - (nullptr != session->sessionCompleteCallback) && - (nullptr != session->sessionMessage.get_source_control_function()) && - (ControlFunction::Type::Internal == session->sessionMessage.get_source_control_function()->get_type())) + else { - session->sessionCompleteCallback(session->sessionMessage.get_identifier().get_parameter_group_number(), - session->get_message_data_length(), - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - success, - session->parent); + CANStackLogger::warn("[TP]: Received End Of Message Acknowledgement for 0x%05X while no session existed for this source and destination, ignoring.", parameterGroupNumber); } } - bool TransportProtocolManager::send_broadcast_announce_message(TransportProtocolSession *session) const + void TransportProtocolManager::process_abort(const std::shared_ptr source, + const std::shared_ptr destination, + std::uint32_t parameterGroupNumber, + TransportProtocolManager::ConnectionAbortReason reason) { - bool retVal = false; + bool foundSession = false; - if (nullptr != session) + auto session = get_session(source, destination); + if ((nullptr != session) && (session->get_parameter_group_number() == parameterGroupNumber)) { - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR, - static_cast(session->get_message_data_length() & 0xFF), - static_cast((session->get_message_data_length() >> 8) & 0xFF), - session->packetCount, - 0xFF, - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - nullptr, - CANIdentifier::CANPriority::PriorityDefault6); + foundSession = true; + CANStackLogger::error("[TP]: Received an abort (reason=%hu) for an rx session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); + close_session(session, false); + } + session = get_session(destination, source); + if ((nullptr != session) && (session->get_parameter_group_number() == parameterGroupNumber)) + { + foundSession = true; + CANStackLogger::error("[TP]: Received an abort (reason=%hu) for a tx session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); + close_session(session, false); + } + + if (!foundSession) + { + CANStackLogger::warn("[TP]: Received an abort (reason=%hu) with no matching session for parameterGroupNumber 0x%05X", static_cast(reason), parameterGroupNumber); } - return retVal; } - bool TransportProtocolManager::send_clear_to_send(TransportProtocolSession *session) const + void TransportProtocolManager::process_connection_management_message(const CANMessage &message) { - bool retVal = false; + if (CAN_DATA_LENGTH != message.get_data_length()) + { + CANStackLogger::warn("[TP]: Received a Connection Management message of invalid length %hu", message.get_data_length()); + return; + } - if (nullptr != session) + const auto parameterGroupNumber = message.get_uint24_at(5); + + switch (message.get_uint8_at(0)) { - std::uint8_t packetsRemaining = (session->packetCount - session->processedPacketsThisSession); - std::uint8_t packetsThisSegment; + case BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR: + { + if (message.is_broadcast()) + { + const auto totalMessageSize = message.get_uint16_at(1); + const auto totalNumberOfPackets = message.get_uint8_at(3); + process_broadcast_announce_message(message.get_source_control_function(), + parameterGroupNumber, + totalMessageSize, + totalNumberOfPackets); + } + else + { + CANStackLogger::warn("[TP]: Received a Broadcast Announcement Message (BAM) with a non-global destination, ignoring"); + } + } + break; - if (session->clearToSendPacketMax < packetsRemaining) + case REQUEST_TO_SEND_MULTIPLEXOR: { - packetsThisSegment = session->clearToSendPacketMax; + if (message.is_broadcast()) + { + CANStackLogger::warn("[TP]: Received a Request to Send (RTS) message with a global destination, ignoring"); + } + else + { + const auto totalMessageSize = message.get_uint16_at(1); + const auto totalNumberOfPackets = message.get_uint8_at(3); + const auto clearToSendPacketMax = message.get_uint8_at(4); + process_request_to_send(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + totalMessageSize, + totalNumberOfPackets, + clearToSendPacketMax); + } } - else + break; + + case CLEAR_TO_SEND_MULTIPLEXOR: + { + if (message.is_broadcast()) + { + CANStackLogger::warn("[TP]: Received a Clear to Send (CTS) message with a global destination, ignoring"); + } + else + { + const auto packetsToBeSent = message.get_uint8_at(1); + const auto nextPacketNumber = message.get_uint8_at(2); + process_clear_to_send(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + packetsToBeSent, + nextPacketNumber); + } + } + break; + + case END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR: { - packetsThisSegment = packetsRemaining; + if (message.is_broadcast()) + { + CANStackLogger::warn("[TP]: Received an End of Message Acknowledge message with a global destination, ignoring"); + } + else + { + process_end_of_session_acknowledgement(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber); + } + } + break; + + case CONNECTION_ABORT_MULTIPLEXOR: + { + if (message.is_broadcast()) + { + CANStackLogger::warn("[TP]: Received an Abort message with a global destination, ignoring"); + } + else + { + const auto reason = static_cast(message.get_uint8_at(1)); + process_abort(message.get_source_control_function(), + message.get_destination_control_function(), + parameterGroupNumber, + reason); + } } + break; - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { CLEAR_TO_SEND_MULTIPLEXOR, - packetsThisSegment, - static_cast(session->processedPacketsThisSession + 1), - 0xFF, - 0xFF, - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_destination_control_function()), - session->sessionMessage.get_source_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + default: + { + CANStackLogger::warn("[TP]: Bad Mux in Transport Protocol Connection Management message"); + } + break; } - return retVal; } - bool TransportProtocolManager::send_request_to_send(TransportProtocolSession *session) const + void TransportProtocolManager::process_data_transfer_message(const CANMessage &message) { - bool retVal = false; - - if (nullptr != session) + if (CAN_DATA_LENGTH != message.get_data_length()) { - const std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { REQUEST_TO_SEND_MULTIPLEXOR, - static_cast(session->get_message_data_length() & 0xFF), - static_cast((session->get_message_data_length() >> 8) & 0xFF), - session->packetCount, - 0xFF, - static_cast(session->sessionMessage.get_identifier().get_parameter_group_number() & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 8) & 0xFF), - static_cast((session->sessionMessage.get_identifier().get_parameter_group_number() >> 16) & 0xFF) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + CANStackLogger::warn("[TP]: Received a Data Transfer message of invalid length %hu", message.get_data_length()); + return; } - return retVal; - } - bool TransportProtocolManager::send_end_of_session_acknowledgement(TransportProtocolSession *session) const - { - bool retVal = false; + auto source = message.get_source_control_function(); + auto destination = message.is_broadcast() ? nullptr : message.get_destination_control_function(); + + auto sequenceNumber = message.get_uint8_at(SEQUENCE_NUMBER_DATA_INDEX); + auto session = get_session(source, destination); if (nullptr != session) { - std::uint8_t dataBuffer[CAN_DATA_LENGTH] = { 0 }; - std::uint32_t messageLength = session->get_message_data_length(); - std::uint32_t pgn = session->sessionMessage.get_identifier().get_parameter_group_number(); + if (StateMachineState::WaitForDataTransferPacket != session->state) + { + CANStackLogger::warn("[TP]: Received a Data Transfer message from %hu while not expecting one, sending abort", source->get_address()); + abort_session(session, ConnectionAbortReason::UnexpectedDataTransferPacketReceived); + } + else if (sequenceNumber == session->get_last_sequence_number()) + { + CANStackLogger::error("[TP]: Aborting rx session for 0x%05X due to duplicate sequence number", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::DuplicateSequenceNumber); + } + else if (sequenceNumber == (session->get_last_sequence_number() + 1)) + { + // Convert data type to a vector to allow for manipulation + auto &data = static_cast(session->get_data()); - dataBuffer[0] = END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR; - dataBuffer[1] = static_cast(messageLength); - dataBuffer[2] = static_cast(messageLength >> 8); - dataBuffer[3] = (static_cast((messageLength - 1) / 7) + 1); - dataBuffer[4] = 0xFF; - dataBuffer[5] = static_cast(pgn); - dataBuffer[6] = static_cast(pgn >> 8); - dataBuffer[7] = static_cast(pgn >> 16); + // Correct sequence number, copy the data + for (std::uint8_t i = 0; i < PROTOCOL_BYTES_PER_FRAME; i++) + { + std::uint32_t currentDataIndex = (PROTOCOL_BYTES_PER_FRAME * session->get_last_packet_number()) + i; + if (currentDataIndex < session->get_message_length()) + { + data.set_byte(currentDataIndex, message.get_uint8_at(1 + i)); + } + else + { + // Reached the end of the message, no need to copy any more data + break; + } + } + + session->set_last_sequency_number(sequenceNumber); + if (session->get_number_of_remaining_packets() == 0) + { + // Send End of Message Acknowledgement for sessions with specific destination only + if (!message.is_broadcast()) + { + send_end_of_session_acknowledgement(session); + } - // This message only needs to be sent if we're the recipient. Sanity check the destination is us - if (ControlFunction::Type::Internal == session->sessionMessage.get_destination_control_function()->get_type()) + // Construct the completed message + CANIdentifier identifier(CANIdentifier::Type::Extended, + session->get_parameter_group_number(), + CANIdentifier::CANPriority::PriorityDefault6, + session->is_broadcast() ? CANIdentifier::GLOBAL_ADDRESS : destination->get_address(), + source->get_address()); + CANMessage completedMessage(CANMessage::Type::Receive, + identifier, + std::move(data), + source, + destination, + 0); + + canMessageReceivedCallback(completedMessage); + close_session(session, true); + CANStackLogger::debug("[TP]: Completed rx session for 0x%05X from %hu", session->get_parameter_group_number(), source->get_address()); + } + else if (session->get_cts_number_of_packets_remaining() == 0) + { + send_clear_to_send(session); + } + } + else { - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolCommand), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_destination_control_function()), - session->sessionMessage.get_source_control_function(), - CANIdentifier::CANPriority::PriorityDefault6); + CANStackLogger::error("[TP]: Aborting rx session for 0x%05X due to bad sequence number", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::BadSequenceNumber); } } - else + else if (!message.is_broadcast()) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[TP]: Attempted to send EOM to null session"); + CANStackLogger::warn("[TP]: Received a Data Transfer message from %hu with no matching session, ignoring...", source->get_address()); } - return retVal; } - void TransportProtocolManager::set_state(TransportProtocolSession *session, StateMachineState value) + void TransportProtocolManager::process_message(const CANMessage &message) { - if (nullptr != session) + // TODO: Allow sniffing of messages to all addresses, not just the ones we normally listen to (#297) + if (message.has_valid_source_control_function() && (message.is_destination_our_device() || message.is_broadcast())) { - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - session->state = value; + switch (message.get_identifier().get_parameter_group_number()) + { + case static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement): + { + process_connection_management_message(message); + } + break; + + case static_cast(CANLibParameterGroupNumber::TransportProtocolDataTransfer): + { + process_data_transfer_message(message); + } + break; + + default: + break; + } } } - bool TransportProtocolManager::get_session(TransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination) + bool TransportProtocolManager::protocol_transmit_message(std::uint32_t parameterGroupNumber, + std::unique_ptr &data, + std::shared_ptr source, + std::shared_ptr destination, + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer) { - session = nullptr; + // Return false early if we can't send the message + if ((nullptr == data) || (data->size() <= CAN_DATA_LENGTH) || (data->size() > MAX_PROTOCOL_DATA_LENGTH)) + { + // Invalid message length + return false; + } + else if ((nullptr == source) || (!source->get_address_valid()) || has_session(source, destination)) + { + return false; + } - for (auto i : activeSessions) + // We can handle this message! If we only have a view of the data, let's clone the data, + // so we don't have to worry about it being deleted. + data = data->copy_if_not_owned(std::move(data)); + auto dataLength = static_cast(data->size()); + + auto session = std::make_shared(TransportProtocolSession::Direction::Transmit, + std::move(data), + parameterGroupNumber, + dataLength, + configuration->get_number_of_packets_per_cts_message(), + source, + destination, + sessionCompleteCallback, + parentPointer); + + if (session->is_broadcast()) + { + // Broadcast message + session->set_state(StateMachineState::SendBroadcastAnnounce); + CANStackLogger::debug("[TP]: New broadcast tx session for 0x%05X. Source: %hu", + parameterGroupNumber, + source->get_address()); + } + else { - if ((i->sessionMessage.get_source_control_function() == source) && - (i->sessionMessage.get_destination_control_function() == destination)) + // Destination specific message + session->set_state(StateMachineState::SendRequestToSend); + CANStackLogger::debug("[TP]: New tx session for 0x%05X. Source: %hu, destination: %hu", + parameterGroupNumber, + source->get_address(), + destination->get_address()); + } + activeSessions.push_back(session); + update_state_machine(session); + return true; + } + + void TransportProtocolManager::update() + { + // We use a fancy for loop here to allow us to remove sessions from the list while iterating + for (std::size_t i = activeSessions.size(); i > 0; i--) + { + auto session = activeSessions.at(i - 1); + if (!session->get_source()->get_address_valid()) { - session = i; - break; + CANStackLogger::warn("[TP]: Closing active session as the source control function is no longer valid"); + close_session(session, false); + } + else if (!session->is_broadcast() && !session->get_destination()->get_address_valid()) + { + CANStackLogger::warn("[TP]: Closing active session as the destination control function is no longer valid"); + close_session(session, false); + } + else if (StateMachineState::None != session->state) + { + update_state_machine(session); } } - return (nullptr != session); } - bool TransportProtocolManager::get_session(TransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination, std::uint32_t parameterGroupNumber) + void TransportProtocolManager::send_data_transfer_packets(std::shared_ptr &session) { - bool retVal = false; - session = nullptr; + std::array buffer; + std::uint8_t framesToSend = session->get_cts_number_of_packets_remaining(); + if (session->is_broadcast()) + { + framesToSend = 1; + } + else if (framesToSend > configuration->get_max_number_of_network_manager_protocol_frames_per_update()) + { + framesToSend = configuration->get_max_number_of_network_manager_protocol_frames_per_update(); + } + + // Try and send packets + for (std::uint8_t i = 0; i < framesToSend; i++) + { + buffer[0] = session->get_last_sequence_number() + 1; + + std::uint16_t dataOffset = session->get_last_packet_number() * PROTOCOL_BYTES_PER_FRAME; + for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) + { + std::uint16_t index = dataOffset + j; + if (index < session->get_message_length()) + { + buffer[1 + j] = session->get_data().get_byte(index); + } + else + { + buffer[1 + j] = 0xFF; + } + } + + if (sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolDataTransfer), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + session->get_destination(), + CANIdentifier::CANPriority::PriorityLowest7)) + { + session->set_last_sequency_number(session->get_last_sequence_number() + 1); + } + else + { + // Process more next time protocol is updated + break; + } + } - if ((get_session(session, source, destination)) && - (session->sessionMessage.get_identifier().get_parameter_group_number() == parameterGroupNumber)) + if (session->get_number_of_remaining_packets() == 0) { - retVal = true; + if (session->is_broadcast()) + { + CANStackLogger::debug("[TP]: Completed broadcast tx session for 0x%05X", session->get_parameter_group_number()); + close_session(session, true); + } + else + { + session->set_state(StateMachineState::WaitForEndOfMessageAcknowledge); + } + } + else if ((session->get_cts_number_of_packets_remaining() == 0) && !session->is_broadcast()) + { + session->set_state(StateMachineState::WaitForClearToSend); } - return retVal; } - void TransportProtocolManager::update_state_machine(TransportProtocolSession *session) + void TransportProtocolManager::update_state_machine(std::shared_ptr &session) { - if (nullptr != session) + switch (session->state) { - switch (session->state) + case StateMachineState::None: + break; + + case StateMachineState::SendBroadcastAnnounce: { - case StateMachineState::None: + if (send_broadcast_announce_message(session)) { + session->set_state(StateMachineState::SendDataTransferPackets); } - break; + } + break; - case StateMachineState::ClearToSend: + case StateMachineState::SendRequestToSend: + { + if (send_request_to_send(session)) { - if (send_clear_to_send(session)) - { - set_state(session, StateMachineState::RxDataSession); - } + session->set_state(StateMachineState::WaitForClearToSend); } - break; + } + break; - case StateMachineState::WaitForClearToSend: - case StateMachineState::WaitForEndOfMessageAcknowledge: + case StateMachineState::WaitForClearToSend: + { + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) { - if (SystemTiming::time_expired_ms(session->timestamp_ms, T2_T3_TIMEOUT_MS)) + CANStackLogger::error("[TP]: Timeout tx session for 0x%05X (expected CTS)", session->get_parameter_group_number()); + if (session->get_cts_number_of_packets() > 0) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: Timeout"); + // A connection is only considered established if we've received at least one CTS before + // And we can only abort a connection if it's considered established abort_session(session, ConnectionAbortReason::Timeout); + } + else + { close_session(session, false); } } - break; + } + break; - case StateMachineState::RequestToSend: + case StateMachineState::SendClearToSend: + { + if (send_clear_to_send(session)) { - if (send_request_to_send(session)) - { - set_state(session, StateMachineState::WaitForClearToSend); - } + session->set_state(StateMachineState::WaitForDataTransferPacket); } - break; + } + break; - case StateMachineState::BroadcastAnnounce: + case StateMachineState::SendDataTransferPackets: + { + if (session->is_broadcast() && (session->get_time_since_last_update() < configuration->get_minimum_time_between_transport_protocol_bam_frames())) { - if (send_broadcast_announce_message(session)) - { - set_state(session, StateMachineState::TxDataSession); - } + // Need to wait before sending the next data frame of the broadcast session } - break; - - case StateMachineState::TxDataSession: + else { - bool sessionStillValid = true; - - if ((nullptr != session->sessionMessage.get_destination_control_function()) || (SystemTiming::time_expired_ms(session->timestamp_ms, CANNetworkManager::CANNetwork.get_configuration().get_minimum_time_between_transport_protocol_bam_frames()))) - { - std::uint8_t dataBuffer[CAN_DATA_LENGTH]; - std::uint32_t framesSentThisUpdate = 0; - - // Try and send packets - for (std::uint8_t i = session->lastPacketNumber; i < session->packetCount; i++) - { - dataBuffer[0] = (session->processedPacketsThisSession + 1); - - if (nullptr != session->frameChunkCallback) - { - // Use the callback to get this frame's data - std::uint8_t callbackBuffer[7] = { - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF - }; - std::uint16_t numberBytesLeft = (session->get_message_data_length() - (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)); - - if (numberBytesLeft > PROTOCOL_BYTES_PER_FRAME) - { - numberBytesLeft = PROTOCOL_BYTES_PER_FRAME; - } - - bool callbackSuccessful = session->frameChunkCallback(dataBuffer[0], (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession), numberBytesLeft, callbackBuffer, session->parent); - - if (callbackSuccessful) - { - for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) - { - dataBuffer[1 + j] = callbackBuffer[j]; - } - } - else - { - abort_session(session, ConnectionAbortReason::AnyOtherError); - close_session(session, false); - sessionStillValid = false; - break; - } - } - else - { - // Use the data buffer to get the data for this frame - for (std::uint8_t j = 0; j < PROTOCOL_BYTES_PER_FRAME; j++) - { - std::uint32_t index = (j + (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)); - if (index < session->get_message_data_length()) - { - dataBuffer[1 + j] = session->sessionMessage.get_data()[j + (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession)]; - } - else - { - dataBuffer[1 + j] = 0xFF; - } - } - } - - if (CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::TransportProtocolData), - dataBuffer, - CAN_DATA_LENGTH, - std::static_pointer_cast(session->sessionMessage.get_source_control_function()), - session->sessionMessage.get_destination_control_function(), - CANIdentifier::CANPriority::PriorityLowest7)) - { - framesSentThisUpdate++; - session->lastPacketNumber++; - session->processedPacketsThisSession++; - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - - if (nullptr == session->sessionMessage.get_destination_control_function()) - { - // Need to wait for the frame delay time before continuing BAM session - break; - } - else if (framesSentThisUpdate >= CANNetworkManager::CANNetwork.get_configuration().get_max_number_of_network_manager_protocol_frames_per_update()) - { - break; // Throttle the session - } - } - else - { - // Process more next time protocol is updated - break; - } - } - } + send_data_transfer_packets(session); + } + } + break; - if (sessionStillValid) + case StateMachineState::WaitForDataTransferPacket: + { + if (session->is_broadcast()) + { + // Broadcast message timeout check + if (session->get_time_since_last_update() > T1_TIMEOUT_MS) { - if ((session->lastPacketNumber == (session->packetCount)) && - (session->get_message_data_length() <= (PROTOCOL_BYTES_PER_FRAME * session->processedPacketsThisSession))) - { - if (nullptr == session->sessionMessage.get_destination_control_function()) - { - // BAM is complete - close_session(session, true); - } - else - { - set_state(session, StateMachineState::WaitForEndOfMessageAcknowledge); - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - } - } - else if (session->lastPacketNumber == session->packetCount) - { - set_state(session, StateMachineState::WaitForClearToSend); - session->timestamp_ms = SystemTiming::get_timestamp_ms(); - } + CANStackLogger::warn("[TP]: Broadcast rx session timeout"); + close_session(session, false); } } - break; - - case StateMachineState::RxDataSession: + else if (session->get_cts_number_of_packets_remaining() == session->get_cts_number_of_packets()) { - if (nullptr == session->sessionMessage.get_destination_control_function()) + // Waiting to receive the first data frame after CTS + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) { - // BAM Timeout check - if (SystemTiming::time_expired_ms(session->timestamp_ms, T1_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: BAM Rx Timeout"); - close_session(session, false); - } + CANStackLogger::error("[TP]: Timeout for destination-specific rx session (expected first data frame)"); + abort_session(session, ConnectionAbortReason::Timeout); } - else + } + else + { + // Waiting on sequential data frames + if (session->get_time_since_last_update() > T1_TIMEOUT_MS) { - // CM TP Timeout check - if (SystemTiming::time_expired_ms(session->timestamp_ms, MESSAGE_TR_TIMEOUT_MS)) - { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TP]: CM Rx Timeout"); - abort_session(session, ConnectionAbortReason::Timeout); - close_session(session, false); - } + CANStackLogger::error("[TP]: Timeout for destination-specific rx session (expected sequential data frame)"); + abort_session(session, ConnectionAbortReason::Timeout); } } - break; } + break; + + case StateMachineState::WaitForEndOfMessageAcknowledge: + { + if (session->get_time_since_last_update() > T2_T3_TIMEOUT_MS) + { + CANStackLogger::error("[TP]: Timeout tx session for 0x%05X (expected EOMA)", session->get_parameter_group_number()); + abort_session(session, ConnectionAbortReason::Timeout); + } + } + break; + } + } + + bool TransportProtocolManager::abort_session(std::shared_ptr &session, ConnectionAbortReason reason) + { + bool retVal = false; + std::shared_ptr myControlFunction; + std::shared_ptr partnerControlFunction; + if (TransportProtocolSession::Direction::Transmit == session->get_direction()) + { + myControlFunction = std::static_pointer_cast(session->get_source()); + partnerControlFunction = session->get_destination(); + } + else + { + myControlFunction = std::static_pointer_cast(session->get_destination()); + partnerControlFunction = session->get_source(); + } + + if ((nullptr != myControlFunction) && (nullptr != partnerControlFunction)) + { + retVal = send_abort(myControlFunction, partnerControlFunction, session->get_parameter_group_number(), reason); + } + close_session(session, false); + return retVal; + } + + bool TransportProtocolManager::send_abort(std::shared_ptr sender, + std::shared_ptr receiver, + std::uint32_t parameterGroupNumber, + ConnectionAbortReason reason) const + { + const std::array buffer{ + CONNECTION_ABORT_MULTIPLEXOR, + static_cast(reason), + 0xFF, + 0xFF, + 0xFF, + static_cast(parameterGroupNumber & 0xFF), + static_cast((parameterGroupNumber >> 8) & 0xFF), + static_cast((parameterGroupNumber >> 16) & 0xFF) + }; + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + sender, + receiver, + CANIdentifier::CANPriority::PriorityLowest7); + } + + void TransportProtocolManager::close_session(std::shared_ptr &session, bool successful) + { + session->complete(successful); + + auto sessionLocation = std::find(activeSessions.begin(), activeSessions.end(), session); + if (activeSessions.end() != sessionLocation) + { + activeSessions.erase(sessionLocation); + CANStackLogger::debug("[TP]: Session Closed"); + } + } + + bool TransportProtocolManager::send_broadcast_announce_message(std::shared_ptr &session) const + { + const std::array buffer{ + BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR, + static_cast(session->get_message_length() & 0xFF), + static_cast((session->get_message_length() >> 8) & 0xFF), + session->get_total_number_of_packets(), + 0xFF, + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + nullptr, + CANIdentifier::CANPriority::PriorityLowest7); + } + + bool TransportProtocolManager::send_request_to_send(std::shared_ptr &session) const + { + const std::array buffer{ + REQUEST_TO_SEND_MULTIPLEXOR, + static_cast(session->get_message_length() & 0xFF), + static_cast((session->get_message_length() >> 8) & 0xFF), + session->get_total_number_of_packets(), + session->get_rts_number_of_packet_limit(), + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_source()), + session->get_destination(), + CANIdentifier::CANPriority::PriorityLowest7); + } + + bool TransportProtocolManager::send_clear_to_send(std::shared_ptr &session) const + { + bool retVal = false; + + std::uint8_t packetsThisSegment = session->get_number_of_remaining_packets(); + if (packetsThisSegment > session->get_rts_number_of_packet_limit()) + { + packetsThisSegment = session->get_rts_number_of_packet_limit(); } + else if (packetsThisSegment > 16) + { + //! @todo apply CTS number of packets recommendation of 16 via a configuration option + packetsThisSegment = 16; + } + + const std::array buffer{ + CLEAR_TO_SEND_MULTIPLEXOR, + packetsThisSegment, + static_cast(session->get_last_packet_number() + 1), + 0xFF, + 0xFF, + static_cast(session->get_parameter_group_number() & 0xFF), + static_cast((session->get_parameter_group_number() >> 8) & 0xFF), + static_cast((session->get_parameter_group_number() >> 16) & 0xFF) + }; + retVal = sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_destination()), // Since we're the receiving side, we are the destination of the session + session->get_source(), + CANIdentifier::CANPriority::PriorityLowest7); + if (retVal) + { + session->set_cts_number_of_packets(packetsThisSegment); + session->set_acknowledged_packet_number(session->get_last_packet_number()); + } + return retVal; } + bool TransportProtocolManager::send_end_of_session_acknowledgement(std::shared_ptr &session) const + { + std::uint32_t messageLength = session->get_message_length(); + std::uint32_t parameterGroupNumber = session->get_parameter_group_number(); + + const std::array buffer{ + END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR, + static_cast(messageLength & 0xFF), + static_cast((messageLength >> 8) & 0xFF), + session->get_total_number_of_packets(), + 0xFF, + static_cast(parameterGroupNumber & 0xFF), + static_cast((parameterGroupNumber >> 8) & 0xFF), + static_cast((parameterGroupNumber >> 16) & 0xFF), + }; + + return sendCANFrameCallback(static_cast(CANLibParameterGroupNumber::TransportProtocolConnectionManagement), + CANDataSpan(buffer.data(), buffer.size()), + std::static_pointer_cast(session->get_destination()), // Since we're the receiving side, we are the destination of the session + + session->get_source(), + CANIdentifier::CANPriority::PriorityLowest7); + } + + bool TransportProtocolManager::has_session(std::shared_ptr source, std::shared_ptr destination) + { + return std::any_of(activeSessions.begin(), activeSessions.end(), [&](const std::shared_ptr &session) { + return session->matches(source, destination); + }); + } + + std::shared_ptr TransportProtocolManager::get_session(std::shared_ptr source, + std::shared_ptr destination) + { + auto result = std::find_if(activeSessions.begin(), activeSessions.end(), [&](const std::shared_ptr &session) { + return session->matches(source, destination); + }); + // Instead of returning a pointer, we return by reference to indicate it should not be deleted or stored + return (activeSessions.end() != result) ? (*result) : nullptr; + } + + const std::vector> &TransportProtocolManager::get_sessions() const + { + return activeSessions; + } } diff --git a/src/can_transport_protocol.hpp b/src/can_transport_protocol.hpp index fd6c929..3fd81bf 100644 --- a/src/can_transport_protocol.hpp +++ b/src/can_transport_protocol.hpp @@ -4,232 +4,320 @@ /// @brief A protocol that handles the ISO11783/J1939 transport protocol. /// It handles both the broadcast version (BAM) and and the connection mode version. /// @author Adrian Del Grosso +/// @author Daan Steenbergen /// -/// @copyright 2022 Adrian Del Grosso +/// @copyright 2023 The Open-Agriculture Developers //================================================================================================ #ifndef CAN_TRANSPORT_PROTOCOL_HPP #define CAN_TRANSPORT_PROTOCOL_HPP -#include "can_badge.hpp" -#include "can_control_function.hpp" -#include "can_protocol.hpp" +#include "can_message_frame.hpp" +#include "can_network_configuration.hpp" +#include "can_transport_protocol_base.hpp" namespace isobus { - //================================================================================================ - /// @class TransportProtocolManager - /// + /// @brief A class that handles the ISO11783/J1939 transport protocol. /// @details This class handles transmission and reception of CAN messages up to 1785 bytes. - /// Both broadcast and connection mode are supported. Simply call send_can_message on the - /// network manager with an appropriate data length, and the protocol will be automatically - /// selected to be used. As a note, use of BAM is discouraged, as it has profound + /// Both broadcast and connection mode are supported. Simply call `CANNetworkManager::send_can_message()` + /// with an appropriate data length, and the protocol will be automatically selected to be used. + /// @note The use of multi-frame broadcast messages (BAM) is discouraged, as it has profound /// packet timing implications for your application, and is limited to only 1 active session at a time. /// That session could be busy if you are using DM1 or any other BAM protocol, causing intermittent /// transmit failures from this class. This is not a bug, rather a limitation of the protocol /// definition. - //================================================================================================ - class TransportProtocolManager : public CANLibProtocol + class TransportProtocolManager { public: /// @brief The states that a TP session could be in. Used for the internal state machine. enum class StateMachineState { None, ///< Protocol session is not in progress - ClearToSend, ///< We are sending clear to send message - RxDataSession, ///< Rx data session is in progress - RequestToSend, ///< We are sending the request to send message + SendBroadcastAnnounce, ///< We are sending the broadcast announce message (BAM) + SendRequestToSend, ///< We are sending the request to send message WaitForClearToSend, ///< We are waiting for a clear to send message - BroadcastAnnounce, ///< We are sending the broadcast announce message (BAM) - TxDataSession, ///< A Tx data session is in progress - WaitForEndOfMessageAcknowledge ///< We are waiting for an end of message acknowledgement + SendClearToSend, ///< We are sending clear to send message + WaitForDataTransferPacket, ///< We are waiting for data transfer packets + SendDataTransferPackets, ///< A Tx data session is in progress + WaitForEndOfMessageAcknowledge, ///< We are waiting for an end of message acknowledgement + }; + + /// @brief A list of all defined abort reasons in ISO11783 + enum class ConnectionAbortReason : std::uint8_t + { + Reserved = 0, ///< Reserved, not to be used, but should be tolerated + AlreadyInCMSession = 1, ///< We are already in a connection mode session and can't support another + SystemResourcesNeeded = 2, ///< Session must be aborted because the system needs resources + Timeout = 3, ///< General timeout + ClearToSendReceivedWhileTransferInProgress = 4, ///< A CTS was received while already processing the last CTS + MaximumRetransmitRequestLimitReached = 5, ///< Maximum retries for the data has been reached + UnexpectedDataTransferPacketReceived = 6, ///< A data packet was received outside the proper state + BadSequenceNumber = 7, ///< Incorrect sequence number was received and cannot be recovered + DuplicateSequenceNumber = 8, ///< Re-received a sequence number we've already processed + TotalMessageSizeTooBig = 9, ///< TP Can't support a message this large (>1785 bytes) + AnyOtherError = 250 ///< Any reason not defined in the standard }; - //================================================================================================ - /// @class TransportProtocolSession - /// /// @brief A storage object to keep track of session information internally - //================================================================================================ - class TransportProtocolSession + class TransportProtocolSession : public TransportProtocolSessionBase { public: - /// @brief Enumerates the possible session directions, Rx or Tx - enum class Direction - { - Transmit, ///< We are transmitting a message - Receive ///< We are receiving a message - }; - - /// @brief A useful way to compare sesson objects to each other for equality - bool operator==(const TransportProtocolSession &obj); + /// @brief The constructor for a session, for advanced use only. + /// In most cases, you should use the CANNetworkManager::send_can_message() function to transmit messages. + /// @param[in] direction The direction of the session + /// @param[in] data Data buffer (will be moved into the session) + /// @param[in] parameterGroupNumber The PGN of the message + /// @param[in] totalMessageSize The total size of the message in bytes + /// @param[in] clearToSendPacketMax The maximum number of packets that can be sent per CTS as indicated by the RTS message + /// @param[in] source The source control function + /// @param[in] destination The destination control function + /// @param[in] sessionCompleteCallback A callback for when the session completes + /// @param[in] parentPointer A generic context object for the tx complete and chunk callbacks + TransportProtocolSession(TransportProtocolSessionBase::Direction direction, + std::unique_ptr data, + std::uint32_t parameterGroupNumber, + std::uint16_t totalMessageSize, + std::uint8_t clearToSendPacketMax, + std::shared_ptr source, + std::shared_ptr destination, + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer); + + /// @brief Get the state of the session + /// @return The state of the session + StateMachineState get_state() const; /// @brief Get the total number of bytes that will be sent or received in this session /// @return The length of the message in number of bytes - std::uint32_t get_message_data_length() const; + std::uint16_t get_message_length() const; - private: + /// @brief Get whether or not this session is a broadcast session (BAM) + /// @return True if this session is a broadcast session, false if not + bool is_broadcast() const; + + /// @brief Get the number of bytes that have been sent or received in this session + /// @return The number of bytes that have been sent or received + std::uint32_t get_total_bytes_transferred() const override; + + protected: friend class TransportProtocolManager; ///< Allows the TP manager full access - /// @brief The constructor for a TP session - /// @param[in] sessionDirection Tx or Rx - /// @param[in] canPortIndex The CAN channel index for the session - TransportProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex); + /// @brief Set the state of the session + /// @param[in] value The state to set the session to + void set_state(StateMachineState value); + + /// @brief Get the number of packets to be sent in response to the current CTS + /// @return The number of packets to be sent in response to the current CTS + std::uint8_t get_cts_number_of_packets_remaining() const; + + /// @brief Set the number of packets to be sent in response to the curent CTS + /// @param[in] value The number of packets to be sent in response to the curent CTS + void set_cts_number_of_packets(std::uint8_t value); + + /// @brief Get the number of packets that can be sent in response to the current CTS + /// @return The number of packets that can be sent in response to the current CTS + std::uint8_t get_cts_number_of_packets() const; + + /// @brief Get the maximum number of packets that can be sent per CTS as indicated by the RTS message + /// @return The maximum number of packets that can be sent per CTS as indicated by the RTS message + std::uint8_t get_rts_number_of_packet_limit() const; + + /// @brief Get the last sequence number that was processed + /// @return The last sequence number that was processed + std::uint8_t get_last_sequence_number() const; - /// @brief The destructor for a TP session - ~TransportProtocolSession() = default; + /// @brief Get the last packet number that was processed + /// @return The last packet number that was processed + std::uint8_t get_last_packet_number() const; + /// @brief Set the last sequence number that will be processed + /// @param[in] value The last sequence number that will be processed + void set_last_sequency_number(std::uint8_t value); + + /// @brief Set the last acknowledged packet number by the receiver + /// @param[in] value The last acknowledged packet number by the receiver + void set_acknowledged_packet_number(std::uint8_t value); + + /// @brief Get the number of packets that remain to be sent or received in this session + /// @return The number of packets that remain to be sent or received in this session + std::uint8_t get_number_of_remaining_packets() const; + + /// @brief Get the total number of packets that will be sent or received in this session + /// @return The total number of packets that will be sent or received in this session + std::uint8_t get_total_number_of_packets() const; + + private: StateMachineState state = StateMachineState::None; ///< The state machine state for this session - CANMessage sessionMessage; ///< A CAN message is used in the session to represent and store data like PGN - TransmitCompleteCallback sessionCompleteCallback = nullptr; ///< A callback that is to be called when the session is completed - DataChunkCallback frameChunkCallback = nullptr; ///< A callback that might be used to get chunks of data to send - std::uint32_t frameChunkCallbackMessageLength = 0; ///< The length of the message that is being sent in chunks - void *parent = nullptr; ///< A generic context variable that helps identify what object callbacks are destined for. Can be nullptr - std::uint32_t timestamp_ms = 0; ///< A timestamp used to track session timeouts - std::uint16_t lastPacketNumber = 0; ///< The last processed sequence number for this set of packets - std::uint8_t packetCount = 0; ///< The total number of packets to receive or send in this session - std::uint8_t processedPacketsThisSession = 0; ///< The total processed packet count for the whole session so far - std::uint8_t clearToSendPacketMax = 0; ///< The max packets that can be sent per CTS as indicated by the RTS message - const Direction sessionDirection; ///< Represents Tx or Rx session - }; - /// @brief A list of all defined abort reasons in ISO11783 - enum class ConnectionAbortReason : std::uint8_t - { - Reserved = 0, ///< Reserved, not to be used, but should be tolerated - AlreadyInCMSession = 1, ///< We are already in a connection mode session and can't support another - SystemResourcesNeeded = 2, ///< Session must be aborted because the system needs resources - Timeout = 3, ///< General timeout - ClearToSendReceivedWhileTransferInProgress = 4, ///< A CTS was received while already processing the last CTS - MaximumRetransmitRequestLimitReached = 5, ///< Maximum retries for the data has been reached - UnexpectedDataTransferPacketReceived = 6, ///< A data packet was received outside the proper state - BadSequenceNumber = 7, ///< Incorrect sequence number was received and cannot be recovered - DuplicateSequenceNumber = 8, ///< Re-received a sequence number we've already processed - TotalMessageSizeTooBig = 9, ///< TP Can't support a message this large (>1785 bytes) - AnyOtherError = 250 ///< Any other error not enumerated above, 0xFE + std::uint8_t lastSequenceNumber = 0; ///< The last processed sequence number for this set of packets + std::uint8_t lastAcknowledgedPacketNumber = 0; ///< The last acknowledged packet number by the receiver + std::uint8_t clearToSendPacketCount = 0; ///< The number of packets to be sent in response to one CTS + std::uint8_t clearToSendPacketCountMax = 0xFF; ///< The max packets that can be sent per CTS as indicated by the RTS message }; - static constexpr std::uint32_t REQUEST_TO_SEND_MULTIPLEXOR = 0x10; ///< TP.CM_RTS Multiplexor - static constexpr std::uint32_t CLEAR_TO_SEND_MULTIPLEXOR = 0x11; ///< TP.CM_CTS Multiplexor - static constexpr std::uint32_t END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR = 0x13; ///< TP.CM_EOM_ACK Multiplexor - static constexpr std::uint32_t BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR = 0x20; ///< TP.BAM Multiplexor - static constexpr std::uint32_t CONNECTION_ABORT_MULTIPLEXOR = 0xFF; ///< Abort multiplexor + static constexpr std::uint32_t REQUEST_TO_SEND_MULTIPLEXOR = 0x10; ///< (16) TP.CM_RTS Multiplexor + static constexpr std::uint32_t CLEAR_TO_SEND_MULTIPLEXOR = 0x11; ///< (17) TP.CM_CTS Multiplexor + static constexpr std::uint32_t END_OF_MESSAGE_ACKNOWLEDGE_MULTIPLEXOR = 0x13; ///< (19) TP.CM_EOM_ACK Multiplexor + static constexpr std::uint32_t BROADCAST_ANNOUNCE_MESSAGE_MULTIPLEXOR = 0x20; ///< (32) TP.BAM Multiplexor + static constexpr std::uint32_t CONNECTION_ABORT_MULTIPLEXOR = 0xFF; ///< (255) Abort multiplexor static constexpr std::uint32_t MAX_PROTOCOL_DATA_LENGTH = 1785; ///< The max number of bytes that this protocol can transfer - static constexpr std::uint32_t T1_TIMEOUT_MS = 750; ///< The t1 timeout as defined by the standard - static constexpr std::uint32_t T2_T3_TIMEOUT_MS = 1250; ///< The t2/t3 timeouts as defined by the standard - static constexpr std::uint32_t T4_TIMEOUT_MS = 1050; ///< The t4 timeout as defined by the standard + static constexpr std::uint16_t T1_TIMEOUT_MS = 750; ///< The t1 timeout as defined by the standard + static constexpr std::uint16_t T2_T3_TIMEOUT_MS = 1250; ///< The t2/t3 timeouts as defined by the standard + static constexpr std::uint16_t T4_TIMEOUT_MS = 1050; ///< The t4 timeout as defined by the standard + static constexpr std::uint8_t R_TIMEOUT_MS = 200; ///< The Tr Timeout as defined by the standard static constexpr std::uint8_t SEQUENCE_NUMBER_DATA_INDEX = 0; ///< The index of the sequence number in a frame - static constexpr std::uint8_t MESSAGE_TR_TIMEOUT_MS = 200; ///< The Tr Timeout as defined by the standard static constexpr std::uint8_t PROTOCOL_BYTES_PER_FRAME = 7; ///< The number of payload bytes per frame minus overhead of sequence number - /// @brief The constructor for the TransportProtocolManager - TransportProtocolManager() = default; + /// @brief The constructor for the TransportProtocolManager, for advanced use only. + /// In most cases, you should use the CANNetworkManager::send_can_message() function to transmit messages. + /// @param[in] sendCANFrameCallback A callback for sending a CAN frame to hardware + /// @param[in] canMessageReceivedCallback A callback for when a complete CAN message is received using the TP protocol + /// @param[in] configuration The configuration to use for this protocol + TransportProtocolManager(const CANMessageFrameCallback &sendCANFrameCallback, + const CANMessageCallback &canMessageReceivedCallback, + const CANNetworkConfiguration *configuration); - /// @brief The destructor for the TransportProtocolManager - ~TransportProtocolManager() final; + /// @brief Updates all sessions managed by this protocol manager instance. + void update(); - /// @brief The protocol's initializer function - void initialize(CANLibBadge) override; + /// @brief Checks if the source and destination control function have an active session/connection. + /// @param[in] source The source control function for the session + /// @param[in] destination The destination control function for the session + /// @returns true if a matching session was found, false if not + bool has_session(std::shared_ptr source, std::shared_ptr destination); - /// @brief A generic way for a protocol to process a received message - /// @param[in] message A received CAN message - void process_message(const CANMessage &message) override; + /// @brief Gets all the active transport protocol sessions that are currently active + /// @note The list returns pointers to the transport protocol sessions, but they can disappear at any time + /// @returns A list of all the active transport protocol sessions + const std::vector> &get_sessions() const; /// @brief A generic way for a protocol to process a received message /// @param[in] message A received CAN message - /// @param[in] parent Provides the context to the actual TP manager object - static void process_message(const CANMessage &message, void *parent); + void process_message(const CANMessage &message); /// @brief The network manager calls this to see if the protocol can accept a long CAN message for processing /// @param[in] parameterGroupNumber The PGN of the message /// @param[in] data The data to be sent - /// @param[in] messageLength The length of the data to be sent /// @param[in] source The source control function /// @param[in] destination The destination control function - /// @param[in] transmitCompleteCallback A callback for when the protocol completes its work + /// @param[in] sessionCompleteCallback A callback for when the protocol completes its work /// @param[in] parentPointer A generic context object for the tx complete and chunk callbacks - /// @param[in] frameChunkCallback A callback to get some data to send /// @returns true if the message was accepted by the protocol for processing bool protocol_transmit_message(std::uint32_t parameterGroupNumber, - const std::uint8_t *data, - std::uint32_t messageLength, + std::unique_ptr &data, std::shared_ptr source, std::shared_ptr destination, - TransmitCompleteCallback transmitCompleteCallback, - void *parentPointer, - DataChunkCallback frameChunkCallback) override; - - /// @brief Updates the protocol cyclically - void update(CANLibBadge) override; + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer); private: /// @brief Aborts the session with the specified abort reason. Sends a CAN message. /// @param[in] session The session to abort /// @param[in] reason The reason we're aborting the session /// @returns true if the abort was send OK, false if not sent - bool abort_session(TransportProtocolSession *session, ConnectionAbortReason reason); + bool abort_session(std::shared_ptr &session, ConnectionAbortReason reason); - /// @brief Aborts Tp with no corresponding session with the specified abort reason. Sends a CAN message. + /// @brief Send an abort with no corresponding session with the specified abort reason. Sends a CAN message. + /// @param[in] sender The sender of the abort + /// @param[in] receiver The receiver of the abort /// @param[in] parameterGroupNumber The PGN of the TP "session" we're aborting /// @param[in] reason The reason we're aborting the session - /// @param[in] source The source control function from which we'll send the abort - /// @param[in] destination The destination control function to which we'll send the abort /// @returns true if the abort was send OK, false if not sent - bool abort_session(std::uint32_t parameterGroupNumber, ConnectionAbortReason reason, std::shared_ptr source, std::shared_ptr destination); + bool send_abort(std::shared_ptr sender, + std::shared_ptr receiver, + std::uint32_t parameterGroupNumber, + ConnectionAbortReason reason) const; /// @brief Gracefully closes a session to prepare for a new session /// @param[in] session The session to close - /// @param[in] successfull Denotes if the session was successful - void close_session(TransportProtocolSession *session, bool successfull); - - /// @brief Processes end of session callbacks - /// @param[in] session The session we've just completed - /// @param[in] success Denotes if the session was successful - void process_session_complete_callback(TransportProtocolSession *session, bool success); + /// @param[in] successful Denotes if the session was successful + void close_session(std::shared_ptr &session, bool successful); /// @brief Sends the "broadcast announce" message /// @param[in] session The session for which we're sending the BAM /// @returns true if the BAM was sent, false if sending was not successful - bool send_broadcast_announce_message(TransportProtocolSession *session) const; - - /// @brief Sends the "clear to send" message - /// @param[in] session The session for which we're sending the CTS - /// @returns true if the CTS was sent, false if sending was not successful - bool send_clear_to_send(TransportProtocolSession *session) const; + bool send_broadcast_announce_message(std::shared_ptr &session) const; /// @brief Sends the "request to send" message as part of initiating a transmit /// @param[in] session The session for which we're sending the RTS /// @returns true if the RTS was sent, false if sending was not successful - bool send_request_to_send(TransportProtocolSession *session) const; + bool send_request_to_send(std::shared_ptr &session) const; + + /// @brief Sends the "clear to send" message + /// @param[in] session The session for which we're sending the CTS + /// @returns true if the CTS was sent, false if sending was not successful + bool send_clear_to_send(std::shared_ptr &session) const; /// @brief Sends the "end of message acknowledgement" message for the provided session /// @param[in] session The session for which we're sending the EOM ACK /// @returns true if the EOM was sent, false if sending was not successful - bool send_end_of_session_acknowledgement(TransportProtocolSession *session) const; - - /// @brief Sets the state machine state of the TP session - /// @param[in] session The session to update - /// @param[in] value The state to update the session to - void set_state(TransportProtocolSession *session, StateMachineState value); - - /// @brief Gets a TP session from the passed in source and destination combination - /// @param[in] source The source control function for the session - /// @param[in] destination The destination control function for the session - /// @param[out] session The found session, or nullptr if no session matched the supplied parameters - bool get_session(TransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination); + bool send_end_of_session_acknowledgement(std::shared_ptr &session) const; + + ///@brief Sends data transfer packets for the specified TransportProtocolSession. + /// @param[in] session The TransportProtocolSession for which to send data transfer packets. + void send_data_transfer_packets(std::shared_ptr &session); + + /// @brief Processes a broadcast announce message. + /// @param[in] source The source control function that sent the broadcast announce message. + /// @param[in] parameterGroupNumber The Parameter Group Number of the broadcast announce message. + /// @param[in] totalMessageSize The total size of the broadcast announce message. + /// @param[in] totalNumberOfPackets The total number of packets in the broadcast announce message. + void process_broadcast_announce_message(const std::shared_ptr source, std::uint32_t parameterGroupNumber, std::uint16_t totalMessageSize, std::uint8_t totalNumberOfPackets); + + /// @brief Processes a request to send a message over the CAN transport protocol. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The Parameter Group Number of the message. + /// @param[in] totalMessageSize The total size of the message in bytes. + /// @param[in] totalNumberOfPackets The total number of packets to be sent. + /// @param[in] clearToSendPacketMax The maximum number of clear to send packets that can be sent. + void process_request_to_send(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint16_t totalMessageSize, std::uint8_t totalNumberOfPackets, std::uint8_t clearToSendPacketMax); + + /// @brief Processes the Clear To Send (CTS) message. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The Parameter Group Number (PGN) of the message. + /// @param[in] packetsToBeSent The number of packets to be sent. + /// @param[in] nextPacketNumber The next packet number. + void process_clear_to_send(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, std::uint8_t packetsToBeSent, std::uint8_t nextPacketNumber); + + /// @brief Processes the end of session acknowledgement. + /// @param[in] source The source control function. + /// @param[in] destination The destination control function. + /// @param[in] parameterGroupNumber The parameter group number. + void process_end_of_session_acknowledgement(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber); + + /// @brief Processes an abort message in the CAN transport protocol. + /// @param[in] source The shared pointer to the source control function. + /// @param[in] destination The shared pointer to the destination control function. + /// @param[in] parameterGroupNumber The PGN (Parameter Group Number) of the message. + /// @param[in] reason The reason for the connection abort. + void process_abort(const std::shared_ptr source, const std::shared_ptr destination, std::uint32_t parameterGroupNumber, TransportProtocolManager::ConnectionAbortReason reason); + + /// @brief Processes a connection management message. + /// @param[in] message The CAN message to be processed. + void process_connection_management_message(const CANMessage &message); + + /// @brief Processes a data transfer message. + /// @param[in] message The CAN message to be processed. + void process_data_transfer_message(const CANMessage &message); /// @brief Gets a TP session from the passed in source and destination and PGN combination /// @param[in] source The source control function for the session /// @param[in] destination The destination control function for the session - /// @param[in] parameterGroupNumber The PGN of the session - /// @param[out] session The found session, or nullptr if no session matched the supplied parameters - bool get_session(TransportProtocolSession *&session, std::shared_ptr source, std::shared_ptr destination, std::uint32_t parameterGroupNumber); + /// @returns a matching session, or nullptr if no session matched the supplied parameters + std::shared_ptr get_session(std::shared_ptr source, std::shared_ptr destination); - /// @brief Updates the state machine of a Tp session + /// @brief Update the state machine for the passed in session /// @param[in] session The session to update - void update_state_machine(TransportProtocolSession *session); + void update_state_machine(std::shared_ptr &session); - std::vector activeSessions; ///< A list of all active TP sessions + std::vector> activeSessions; ///< A list of all active TP sessions + const CANMessageFrameCallback sendCANFrameCallback; ///< A callback for sending a CAN frame + const CANMessageCallback canMessageReceivedCallback; ///< A callback for when a complete CAN message is received using the TP protocol + const CANNetworkConfiguration *configuration; ///< The configuration to use for this protocol }; } // namespace isobus diff --git a/src/can_transport_protocol_base.cpp b/src/can_transport_protocol_base.cpp new file mode 100644 index 0000000..0cf8192 --- /dev/null +++ b/src/can_transport_protocol_base.cpp @@ -0,0 +1,106 @@ +//================================================================================================ +/// @file can_transport_protocol.cpp +/// +/// @brief Abstract base class for CAN transport protocols. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ + +#include "can_transport_protocol_base.hpp" +#include "can_internal_control_function.hpp" +#include "system_timing.hpp" + +namespace isobus +{ + TransportProtocolSessionBase::TransportProtocolSessionBase(TransportProtocolSessionBase::Direction direction, + std::unique_ptr data, + std::uint32_t parameterGroupNumber, + std::uint32_t totalMessageSize, + std::shared_ptr source, + std::shared_ptr destination, + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer) : + direction(direction), + parameterGroupNumber(parameterGroupNumber), + data(std::move(data)), + source(source), + destination(destination), + totalMessageSize(totalMessageSize), + sessionCompleteCallback(sessionCompleteCallback), + parent(parentPointer) + { + } + + bool TransportProtocolSessionBase::operator==(const TransportProtocolSessionBase &obj) const + { + return ((source == obj.source) && (destination == obj.destination) && (parameterGroupNumber == obj.parameterGroupNumber)); + } + + bool TransportProtocolSessionBase::matches(std::shared_ptr other_source, std::shared_ptr other_destination) const + { + return ((source == other_source) && (destination == other_destination)); + } + + TransportProtocolSessionBase::Direction TransportProtocolSessionBase::get_direction() const + { + return direction; + } + + CANMessageData &TransportProtocolSessionBase::get_data() const + { + return *data; + } + + std::uint32_t TransportProtocolSessionBase::get_message_length() const + { + return totalMessageSize; + } + + std::shared_ptr TransportProtocolSessionBase::get_source() const + { + return source; + } + + float TransportProtocolSessionBase::get_percentage_bytes_transferred() const + { + if (0 == get_message_length()) + { + return 0.0f; + } + return static_cast(get_total_bytes_transferred()) / static_cast(get_message_length()) * 100.0f; + } + + std::shared_ptr TransportProtocolSessionBase::get_destination() const + { + return destination; + } + + std::uint32_t TransportProtocolSessionBase::get_parameter_group_number() const + { + return parameterGroupNumber; + } + + void isobus::TransportProtocolSessionBase::update_timestamp() + { + timestamp_ms = SystemTiming::get_timestamp_ms(); + } + + std::uint32_t TransportProtocolSessionBase::get_time_since_last_update() const + { + return SystemTiming::get_time_elapsed_ms(timestamp_ms); + } + + void TransportProtocolSessionBase::complete(bool success) const + { + if ((nullptr != sessionCompleteCallback) && (Direction::Transmit == direction)) + { + sessionCompleteCallback(get_parameter_group_number(), + get_message_length(), + std::static_pointer_cast(source), + get_destination(), + success, + parent); + } + } +} diff --git a/src/can_transport_protocol_base.hpp b/src/can_transport_protocol_base.hpp new file mode 100644 index 0000000..f39bcf9 --- /dev/null +++ b/src/can_transport_protocol_base.hpp @@ -0,0 +1,133 @@ +//================================================================================================ +/// @file can_transport_protocol_base.hpp +/// +/// @brief Abstract base class for CAN transport protocols. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ + +#ifndef CAN_TRANSPORT_PROTOCOL_BASE_HPP +#define CAN_TRANSPORT_PROTOCOL_BASE_HPP + +#include "can_control_function.hpp" +#include "can_message.hpp" +#include "can_message_data.hpp" + +namespace isobus +{ + /// @brief An object to keep track of session information internally + class TransportProtocolSessionBase + { + public: + /// @brief Enumerates the possible session directions + enum class Direction + { + Transmit, ///< We are transmitting a message + Receive ///< We are receiving a message + }; + + /// @brief The constructor for a session + /// @param[in] direction The direction of the session + /// @param[in] data Data buffer (will be moved into the session) + /// @param[in] parameterGroupNumber The PGN of the message + /// @param[in] totalMessageSize The total size of the message in bytes + /// @param[in] source The source control function + /// @param[in] destination The destination control function + /// @param[in] sessionCompleteCallback A callback for when the session completes + /// @param[in] parentPointer A generic context object for the tx complete and chunk callbacks + TransportProtocolSessionBase(TransportProtocolSessionBase::Direction direction, + std::unique_ptr data, + std::uint32_t parameterGroupNumber, + std::uint32_t totalMessageSize, + std::shared_ptr source, + std::shared_ptr destination, + TransmitCompleteCallback sessionCompleteCallback, + void *parentPointer); + + /// @brief The move constructor + /// @param[in] other The object to move + TransportProtocolSessionBase(TransportProtocolSessionBase &&other) = default; + + /// @brief The move assignment operator + /// @param[in] other The object to move + /// @return A reference to the moved object + TransportProtocolSessionBase &operator=(TransportProtocolSessionBase &&other) = default; + + /// @brief The destructor for a session + virtual ~TransportProtocolSessionBase() = default; + + /// @brief Get the direction of the session + /// @return The direction of the session + Direction get_direction() const; + + /// @brief A useful way to compare session objects to each other for equality, + /// @details A session is considered equal when the source and destination control functions + /// and parameter group number match. Note that we don't compare the super class, + /// so this should only be used to compare sessions of the same type. + /// @param[in] obj The object to compare to + /// @returns true if the objects are equal, false if not + bool operator==(const TransportProtocolSessionBase &obj) const; + + /// @brief Checks if the source and destination control functions match the given control functions. + /// @param[in] other_source The control function to compare with the source control function. + /// @param[in] other_destination The control function to compare with the destination control function. + /// @returns True if the source and destination control functions match the given control functions, false otherwise. + bool matches(std::shared_ptr other_source, std::shared_ptr other_destination) const; + + /// @brief Get the data buffer for the session + /// @return The data buffer for the session + CANMessageData &get_data() const; + + /// @brief Get the total number of bytes that will be sent or received in this session + /// @return The length of the message in number of bytes + std::uint32_t get_message_length() const; + + /// @brief Get the number of bytes that have been sent or received in this session + /// @return The number of bytes that have been sent or received + virtual std::uint32_t get_total_bytes_transferred() const = 0; + + /// @brief Get the percentage of bytes that have been sent or received in this session + /// @return The percentage of bytes that have been sent or received (between 0 and 100) + float get_percentage_bytes_transferred() const; + + /// @brief Get the control function that is sending the message + /// @return The source control function + std::shared_ptr get_source() const; + + /// @brief Get the control function that is receiving the message + /// @return The destination control function + std::shared_ptr get_destination() const; + + /// @brief Get the parameter group number of the message + /// @return The PGN of the message + std::uint32_t get_parameter_group_number() const; + + protected: + /// @brief Update the timestamp of the session + void update_timestamp(); + + /// @brief Get the time that has passed since the last update of the timestamp + /// @return The duration in milliseconds + std::uint32_t get_time_since_last_update() const; + + /// @brief Complete the session + /// @param[in] success True if the session was successful, false otherwise + void complete(bool success) const; + + private: + Direction direction; ///< The direction of the session + std::uint32_t parameterGroupNumber; ///< The PGN of the message + std::unique_ptr data; ///< The data buffer for the message + std::shared_ptr source; ///< The source control function + std::shared_ptr destination; ///< The destination control function + std::uint32_t timestamp_ms = 0; ///< A timestamp used to track session timeouts + + std::uint32_t totalMessageSize; ///< The total size of the message in bytes (the maximum size of a message is from ETP and can fit in an uint32_t) + + TransmitCompleteCallback sessionCompleteCallback = nullptr; ///< A callback that is to be called when the session is completed + void *parent = nullptr; ///< A generic context variable that helps identify what object callbacks are destined for. Can be nullptr + }; +} // namespace isobus + +#endif // CAN_TRANSPORT_PROTOCOL_BASE_HPP diff --git a/src/data_span.hpp b/src/data_span.hpp new file mode 100644 index 0000000..678215d --- /dev/null +++ b/src/data_span.hpp @@ -0,0 +1,79 @@ +//================================================================================================ +/// @file can_message_data.hpp +/// +/// @brief Contains common types and functions for working with an arbitrary amount of items. +/// @author Daan Steenbergen +/// +/// @copyright 2023 Open Agriculture +//================================================================================================ +#ifndef DATA_SPAN_HPP +#define DATA_SPAN_HPP + +#include +#include +#include + +namespace isobus +{ + //================================================================================================ + /// @class DataSpan + /// + /// @brief A class that represents a span of data of arbitrary length. + //================================================================================================ + template + class DataSpan + { + public: + /// @brief Construct a new DataSpan object of a writeable array. + /// @param ptr pointer to the buffer to use. + /// @param len The number of elements in the buffer. + DataSpan(T *ptr, std::size_t size) : + ptr(ptr), + _size(size) + { + } + + /// @brief Get the element at the given index. + /// @param index The index of the element to get. + /// @return The element at the given index. + T &operator[](std::size_t index) + { + return ptr[index * sizeof(T)]; + } + + /// @brief Get the element at the given index. + /// @param index The index of the element to get. + /// @return The element at the given index. + T const &operator[](std::size_t index) const + { + return ptr[index * sizeof(T)]; + } + + /// @brief Get the size of the data span. + /// @return The size of the data span. + std::size_t size() const + { + return _size; + } + + /// @brief Get the begin iterator. + /// @return The begin iterator. + T *begin() const + { + return ptr; + } + + /// @brief Get the end iterator. + /// @return The end iterator. + T *end() const + { + return ptr + _size * sizeof(T); + } + + private: + T *ptr; + std::size_t _size; + bool _isConst; + }; +} +#endif // DATA_SPAN_HPP diff --git a/src/event_dispatcher.hpp b/src/event_dispatcher.hpp index bb3cdca..0b91c26 100644 --- a/src/event_dispatcher.hpp +++ b/src/event_dispatcher.hpp @@ -4,52 +4,58 @@ /// @brief An object to represent a dispatcher that can invoke callbacks in a thread-safe manner. /// @author Daan Steenbergen /// -/// @copyright 2023 Adrian Del Grosso +/// @copyright 2024 The Open-Agriculture Developers //================================================================================================ #ifndef EVENT_DISPATCHER_HPP #define EVENT_DISPATCHER_HPP +#include "thread_synchronization.hpp" + #include #include #include -#include - -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO -#include -#endif +#include +#include namespace isobus { - //================================================================================================ - /// @class EventDispatcher - /// + using EventCallbackHandle = std::size_t; + /// @brief A dispatcher that notifies listeners when an event is invoked. - //================================================================================================ template class EventDispatcher { public: + using Callback = std::function; + /// @brief Register a callback to be invoked when the event is invoked. /// @param callback The callback to register. - /// @return A shared pointer to the callback. - std::shared_ptr> add_listener(const std::function &callback) + /// @return A unique identifier for the callback, which can be used to remove the listener. + EventCallbackHandle add_listener(const Callback &callback) { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(callbacksMutex); -#endif - auto shared = std::make_shared>(callback); - callbacks.push_back(shared); - return shared; + EventCallbackHandle id = nextId; + nextId += 1; + + LOCK_GUARD(Mutex, callbacksMutex); + if (isExecuting) + { + modifications.push([this, id, callback]() { callbacks[id] = callback; }); + } + else + { + callbacks[id] = callback; + } + return id; } /// @brief Register a callback to be invoked when the event is invoked. /// @param callback The callback to register. /// @param context The context object to pass through to the callback. - /// @return A shared pointer to the contextless callback. + /// @return A unique identifier for the callback, which can be used to remove the listener. template - std::shared_ptr> add_listener(const std::function)> &callback, std::weak_ptr context) + EventCallbackHandle add_listener(const std::function)> &callback, std::weak_ptr context) { - std::function callbackWrapper = [callback, context](const E &...args) { + Callback callbackWrapper = [callback, context](const E &...args) { if (auto contextPtr = context.lock()) { callback(args..., contextPtr); @@ -61,51 +67,59 @@ namespace isobus /// @brief Register an unsafe callback to be invoked when the event is invoked. /// @param callback The callback to register. /// @param context The context object to pass through to the callback. - /// @return A shared pointer to the contextless callback. + /// @return A unique identifier for the callback, which can be used to remove the listener. template - std::shared_ptr> add_unsafe_listener(const std::function)> &callback, std::weak_ptr context) + EventCallbackHandle add_unsafe_listener(const std::function &callback, C *context) { - std::function callbackWrapper = [callback, context](const E &...args) { + Callback callbackWrapper = [callback, context](const E &...args) { callback(args..., context); }; return add_listener(callbackWrapper); } + /// @brief Remove a callback from the list of listeners. + /// @param id The unique identifier of the callback to remove. + void remove_listener(EventCallbackHandle id) noexcept + { + LOCK_GUARD(Mutex, callbacksMutex); + if (isExecuting) + { + modifications.push([this, id]() { callbacks.erase(id); }); + } + else + { + callbacks.erase(id); + } + } + + /// @brief Remove all listeners from the event. + void clear_listeners() noexcept + { + LOCK_GUARD(Mutex, callbacksMutex); + if (isExecuting) + { + modifications.push([this]() { callbacks.clear(); }); + } + else + { + callbacks.clear(); + } + } + /// @brief Get the number of listeners registered to this event. /// @return The number of listeners std::size_t get_listener_count() { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(callbacksMutex); -#endif + LOCK_GUARD(Mutex, callbacksMutex); return callbacks.size(); } - /// @brief Remove expired listeners from the dispatcher - void remove_expired_listeners() - { - auto removeResult = std::remove_if(callbacks.begin(), callbacks.end(), [](std::weak_ptr> &callback) { - return callback.expired(); - }); - callbacks.erase(removeResult, callbacks.end()); - } - - /// @brief Call and event with context that is moved using move semantics to notify all listeners. + /// @brief Call and event with context that is forwarded to all listeners. /// @param args The event context to notify listeners with. /// @return True if the event was successfully invoked, false otherwise. void invoke(E &&...args) { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(callbacksMutex); -#endif - remove_expired_listeners(); - - std::for_each(callbacks.begin(), callbacks.end(), [&args...](std::weak_ptr> &callback) { - if (auto callbackPtr = callback.lock()) - { - (*callbackPtr)(std::forward(args)...); - } - }); + call(args...); } /// @brief Call an event with existing context to notify all listeners. @@ -113,24 +127,38 @@ namespace isobus /// @return True if the event was successfully invoked, false otherwise. void call(const E &...args) { -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::lock_guard lock(callbacksMutex); -#endif - remove_expired_listeners(); + { + // Set flag to indicate we will be reading the list of callbacks, and + // prevent other threads from modifying the list directly during this time + LOCK_GUARD(Mutex, callbacksMutex); + isExecuting = true; + } + + // Execute the callbacks + for (const auto &callback : callbacks) + { + callback.second(args...); + } + + { + LOCK_GUARD(Mutex, callbacksMutex); + isExecuting = false; - std::for_each(callbacks.begin(), callbacks.end(), [&args...](std::weak_ptr> &callback) { - if (auto callbackPtr = callback.lock()) + // Apply pending modifications to the callbacks list + while (!modifications.empty()) { - (*callbackPtr)(args...); + modifications.front()(); + modifications.pop(); } - }); + } } private: - std::vector>> callbacks; ///< The callbacks to invoke -#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - std::mutex callbacksMutex; ///< The mutex to protect the callbacks -#endif + std::unordered_map callbacks; ///< The list of callbacks + bool isExecuting = false; ///< Whether the dispatcher is currently executing an event + std::queue> modifications; ///< The modifications to the callbacks list + Mutex callbacksMutex; ///< The mutex to protect the object from (unwanted) concurrent access + EventCallbackHandle nextId = 0; // Counter for generating unique IDs }; } // namespace isobus diff --git a/src/flex_can_t4_plugin.cpp b/src/flex_can_t4_plugin.cpp index 545f350..ede267b 100644 --- a/src/flex_can_t4_plugin.cpp +++ b/src/flex_can_t4_plugin.cpp @@ -104,7 +104,7 @@ namespace isobus message.id = canFrame.identifier; message.len = canFrame.dataLength; message.flags.extended = true; - message.seq = 1; // Try to get messages to go out sequentially... + message.seq = true; // Ask for sequential transmission memcpy(message.buf, canFrame.data, canFrame.dataLength); if (0 == selectedChannel) diff --git a/src/flex_can_t4_plugin.hpp b/src/flex_can_t4_plugin.hpp index cf4ca47..1623cee 100644 --- a/src/flex_can_t4_plugin.hpp +++ b/src/flex_can_t4_plugin.hpp @@ -56,8 +56,8 @@ namespace isobus static FlexCAN_T4 can0; static FlexCAN_T4 can1; #endif - std::uint8_t selectedChannel; - bool isOpen = false; + std::uint8_t selectedChannel; ///< The channel that this plugin is assigned to + bool isOpen = false; ///< Tracks if the connection is open/connected }; } #endif // FLEX_CAN_T4_PLUGIN_HPP diff --git a/src/isobus_data_dictionary.cpp b/src/isobus_data_dictionary.cpp new file mode 100644 index 0000000..6f4212a --- /dev/null +++ b/src/isobus_data_dictionary.cpp @@ -0,0 +1,747 @@ +//================================================================================================ +/// @file isobus_data_dictionary.cpp +/// +/// @brief This file contains an auto-generated lookup table of all ISOBUS DDIs as defined +/// in ISO11783-11, exported from isobus.net. +/// This file was generated January 25, 2024. +/// @author Adrian Del Grosso +/// @copyright 2024 The Open-Agriculture Developers +//================================================================================================ +#include "isobus_data_dictionary.hpp" + +namespace isobus +{ + const DataDictionary::Entry &DataDictionary::get_entry(std::uint16_t dataDictionaryIdentifier) + { + for (std::uint_fast16_t i = 0; i < sizeof(DDI_ENTRIES) / sizeof(DataDictionary::Entry); i++) + { + if (DDI_ENTRIES[i].ddi == dataDictionaryIdentifier) + { + return DDI_ENTRIES[i]; + } + } + return DEFAULT_ENTRY; + } + + const DataDictionary::Entry DataDictionary::DEFAULT_ENTRY = { 65535, "Unknown", "Unknown", 0.0f }; + + // The table below is auto-generated, and is not to be edited manually. + const DataDictionary::Entry DataDictionary::DDI_ENTRIES[] = { + { 0, "Internal Data Base DDI", "None", 1.0f }, + { 1, "Setpoint Volume Per Area Application Rate as [mm³/m²]", "mm³/m² - Capacity per area unit", 0.01f }, + { 2, "Actual Volume Per Area Application Rate as [mm³/m²]", "mm³/m² - Capacity per area unit", 0.01f }, + { 3, "Default Volume Per Area Application Rate as [mm³/m²]", "mm³/m² - Capacity per area unit", 0.01f }, + { 4, "Minimum Volume Per Area Application Rate as [mm³/m²]", "mm³/m² - Capacity per area unit", 0.01f }, + { 5, "Maximum Volume Per Area Application Rate as [mm³/m²]", "mm³/m² - Capacity per area unit", 0.01f }, + { 6, "Setpoint Mass Per Area Application Rate", "mg/m² - Mass per area unit", 1.0f }, + { 7, "Actual Mass Per Area Application Rate", "mg/m² - Mass per area unit", 1.0f }, + { 8, "Default Mass Per Area Application Rate", "mg/m² - Mass per area unit", 1.0f }, + { 9, "Minimum Mass Per Area Application Rate", "mg/m² - Mass per area unit", 1.0f }, + { 10, "Maximum Mass Per Area Application Rate", "mg/m² - Mass per area unit", 1.0f }, + { 11, "Setpoint Count Per Area Application Rate", "/m² - Quantity per area unit", 0.001f }, + { 12, "Actual Count Per Area Application Rate", "/m² - Quantity per area unit", 0.001f }, + { 13, "Default Count Per Area Application Rate", "/m² - Quantity per area unit", 0.001f }, + { 14, "Minimum Count Per Area Application Rate", "/m² - Quantity per area unit", 0.001f }, + { 15, "Maximum Count Per Area Application Rate", "/m² - Quantity per area unit", 0.001f }, + { 16, "Setpoint Spacing Application Rate", "mm - Length", 1.0f }, + { 17, "Actual Spacing Application Rate", "mm - Length", 1.0f }, + { 18, "Default Spacing Application Rate", "mm - Length", 1.0f }, + { 19, "Minimum Spacing Application Rate", "mm - Length", 1.0f }, + { 20, "Maximum Spacing Application Rate", "mm - Length", 1.0f }, + { 21, "Setpoint Volume Per Volume Application Rate", "mm³/m³ - Capacity per capacity unit", 1.0f }, + { 22, "Actual Volume Per Volume Application Rate", "mm³/m³ - Capacity per capacity unit", 1.0f }, + { 23, "Default Volume Per Volume Application Rate", "mm³/m³ - Capacity per capacity unit", 1.0f }, + { 24, "Minimum Volume Per Volume Application Rate", "mm³/m³ - Capacity per capacity unit", 1.0f }, + { 25, "Maximum Volume Per Volume Application Rate", "mm³/m³ - Capacity per capacity unit", 1.0f }, + { 26, "Setpoint Mass Per Mass Application Rate", "mg/kg - Mass per mass unit", 1.0f }, + { 27, "Actual Mass Per Mass Application Rate", "mg/kg - Mass per mass unit", 1.0f }, + { 28, "Default Mass Per Mass Application Rate", "mg/kg - Mass per mass unit", 1.0f }, + { 29, "Minimum Mass Per Mass Application Rate", "mg/kg - Mass per mass unit", 1.0f }, + { 30, "MaximumMass Per Mass Application Rate", "mg/kg - Mass per mass unit", 1.0f }, + { 31, "Setpoint Volume Per Mass Application Rate", "mm³/kg - Capacity per mass unit", 1.0f }, + { 32, "Actual Volume Per Mass Application Rate", "mm³/kg - Capacity per mass unit", 1.0f }, + { 33, "Default Volume Per Mass Application Rate", "mm³/kg - Capacity per mass unit", 1.0f }, + { 34, "Minimum Volume Per Mass Application Rate", "mm³/kg - Capacity per mass unit", 1.0f }, + { 35, "Maximum Volume Per Mass Application Rate", "mm³/kg - Capacity per mass unit", 1.0f }, + { 36, "Setpoint Volume Per Time Application Rate", "mm³/s - Flow", 1.0f }, + { 37, "Actual Volume Per Time Application Rate", "mm³/s - Flow", 1.0f }, + { 38, "Default Volume Per Time Application Rate", "mm³/s - Flow", 1.0f }, + { 39, "Minimum Volume Per Time Application Rate", "mm³/s - Flow", 1.0f }, + { 40, "Maximum Volume Per Time Application Rate", "mm³/s - Flow", 1.0f }, + { 41, "Setpoint Mass Per Time Application Rate", "mg/s - Mass flow", 1.0f }, + { 42, "Actual Mass Per Time Application Rate", "mg/s - Mass flow", 1.0f }, + { 43, "Default Mass Per Time Application Rate", "mg/s - Mass flow", 1.0f }, + { 44, "Minimum Mass Per Time Application Rate", "mg/s - Mass flow", 1.0f }, + { 45, "Maximum Mass Per Time Application Rate", "mg/s - Mass flow", 1.0f }, + { 46, "Setpoint Count Per Time Application Rate", "/s - Quantity per time unit", 0.001f }, + { 47, "Actual Count Per Time Application Rate", "/s - Quantity per time unit", 0.001f }, + { 48, "Default Count Per Time Application Rate", "/s - Quantity per time unit", 0.001f }, + { 49, "Minimum Count Per Time Application Rate", "/s - Quantity per time unit", 0.001f }, + { 50, "Maximum Count Per Time Application Rate", "/s - Quantity per time unit", 0.001f }, + { 51, "Setpoint Tillage Depth", "mm - Length", 1.0f }, + { 52, "Actual Tillage Depth", "mm - Length", 1.0f }, + { 53, "Default Tillage Depth", "mm - Length", 1.0f }, + { 54, "Minimum Tillage Depth", "mm - Length", 1.0f }, + { 55, "Maximum Tillage Depth", "mm - Length", 1.0f }, + { 56, "Setpoint Seeding Depth", "mm - Length", 1.0f }, + { 57, "Actual Seeding Depth", "mm - Length", 1.0f }, + { 58, "Default Seeding Depth", "mm - Length", 1.0f }, + { 59, "Minimum Seeding Depth", "mm - Length", 1.0f }, + { 60, "Maximum Seeding Depth", "mm - Length", 1.0f }, + { 61, "Setpoint Working Height", "mm - Length", 1.0f }, + { 62, "Actual Working Height", "mm - Length", 1.0f }, + { 63, "Default Working Height", "mm - Length", 1.0f }, + { 64, "Minimum Working Height", "mm - Length", 1.0f }, + { 65, "Maximum Working Height", "mm - Length", 1.0f }, + { 66, "Setpoint Working Width", "mm - Length", 1.0f }, + { 67, "Actual Working Width", "mm - Length", 1.0f }, + { 68, "Default Working Width", "mm - Length", 1.0f }, + { 69, "Minimum Working Width", "mm - Length", 1.0f }, + { 70, "Maximum Working Width", "mm - Length", 1.0f }, + { 71, "Setpoint Volume Content", "ml - Capacity large", 1.0f }, + { 72, "Actual Volume Content", "ml - Capacity large", 1.0f }, + { 73, "Maximum Volume Content", "ml - Capacity large", 1.0f }, + { 74, "Setpoint Mass Content", "g - Mass large", 1.0f }, + { 75, "Actual Mass Content", "g - Mass large", 1.0f }, + { 76, "Maximum Mass Content", "g - Mass large", 1.0f }, + { 77, "Setpoint Count Content", "# - Quantity/Count", 1.0f }, + { 78, "Actual Count Content", "# - Quantity/Count", 1.0f }, + { 79, "Maximum Count Content", "# - Quantity/Count", 1.0f }, + { 80, "Application Total Volume as [L]", "L - Capacity count", 1.0f }, + { 81, "Application Total Mass in [kg]", "kg - Mass", 1.0f }, + { 82, "Application Total Count", "# - Quantity/Count", 1.0f }, + { 83, "Volume Per Area Yield", "ml/m² - Capacity per area large", 1.0f }, + { 84, "Mass Per Area Yield", "mg/m² - Mass per area unit", 1.0f }, + { 85, "Count Per Area Yield", "/m² - Quantity per area unit", 0.001f }, + { 86, "Volume Per Time Yield", "ml/s - Float large", 1.0f }, + { 87, "Mass Per Time Yield", "mg/s - Mass flow", 1.0f }, + { 88, "Count Per Time Yield", "/s - Quantity per time unit", 0.001f }, + { 89, "Yield Total Volume", "L - Quantity per volume", 1.0f }, + { 90, "Yield Total Mass", "kg - Mass", 1.0f }, + { 91, "Yield Total Count", "# - Quantity/Count", 1.0f }, + { 92, "Volume Per Area Crop Loss", "ml/m² - Capacity per area large", 1.0f }, + { 93, "Mass Per Area Crop Loss", "mg/m² - Mass per area unit", 1.0f }, + { 94, "Count Per Area Crop Loss", "/m² - Quantity per area unit", 0.001f }, + { 95, "Volume Per Time Crop Loss", "ml/s - Float large", 1.0f }, + { 96, "Mass Per Time Crop Loss", "mg/s - Mass flow", 1.0f }, + { 97, "Count Per Time Crop Loss", "/s - Quantity per time unit", 0.001f }, + { 98, "Percentage Crop Loss", "ppm - Parts per million", 1.0f }, + { 99, "Crop Moisture", "ppm - Parts per million", 1.0f }, + { 100, "Crop Contamination", "ppm - Parts per million", 1.0f }, + { 101, "Setpoint Bale Width", "mm - Length", 1.0f }, + { 102, "Actual Bale Width", "mm - Length", 1.0f }, + { 103, "Default Bale Width", "mm - Length", 1.0f }, + { 104, "Minimum Bale Width", "mm - Length", 1.0f }, + { 105, "Maximum Bale Width", "mm - Length", 1.0f }, + { 106, "Setpoint Bale Height", "mm - Length", 1.0f }, + { 107, "ActualBaleHeight", "mm - Length", 1.0f }, + { 108, "Default Bale Height", "mm - Length", 1.0f }, + { 109, "Minimum Bale Height", "mm - Length", 1.0f }, + { 110, "Maximum Bale Height", "mm - Length", 1.0f }, + { 111, "Setpoint Bale Size", "mm - Length", 1.0f }, + { 112, "Actual Bale Size", "mm - Length", 1.0f }, + { 113, "Default Bale Size", "mm - Length", 1.0f }, + { 114, "Minimum Bale Size", "mm - Length", 1.0f }, + { 115, "Maximum Bale Size", "mm - Length", 1.0f }, + { 116, "Total Area", "m² - Area", 1.0f }, + { 117, "Effective Total Distance", "mm - Length", 1.0f }, + { 118, "Ineffective Total Distance", "mm - Length", 1.0f }, + { 119, "Effective Total Time", "s - Time count", 1.0f }, + { 120, "Ineffective Total Time", "s - Time count", 1.0f }, + { 121, "Product Density Mass Per Volume", "mg/l - Mass per capacity unit", 1.0f }, + { 122, "Product Density Mass PerCount", "mg/1000 - 1000 seed Mass", 1.0f }, + { 123, "Product Density Volume Per Count", "ml/1000 - Volume per quantity unit", 1.0f }, + { 124, "Auxiliary Valve Scaling Extend", "% - Percent", 0.1f }, + { 125, "Auxiliary Valve Scaling Retract", "% - Percent", 0.1f }, + { 126, "Auxiliary Valve Ramp Extend Up", "ms - Time", 1.0f }, + { 127, "Auxiliary Valve Ramp Extend Down", "ms - Time", 1.0f }, + { 128, "Auxiliary Valve Ramp Retract Up", "ms - Time", 1.0f }, + { 129, "Auxiliary Valve Ramp Retract Down", "ms - Time", 1.0f }, + { 130, "Auxiliary Valve Float Threshold", "% - Percent", 0.1f }, + { 131, "Auxiliary Valve Progressivity Extend", "None", 1.0f }, + { 132, "Auxiliary Valve Progressivity Retract", "None", 1.0f }, + { 133, "Auxiliary Valve Invert Ports", "None", 1.0f }, + { 134, "Device Element Offset X", "mm - Length", 1.0f }, + { 135, "Device Element Offset Y", "mm - Length", 1.0f }, + { 136, "Device Element Offset Z", "mm - Length", 1.0f }, + { 137, "Device Volume Capacity", "ml - Capacity large", 1.0f }, + { 138, "Device Mass Capacity", "g - Mass large", 1.0f }, + { 139, "Device Count Capacity", "# - Quantity/Count", 1.0f }, + { 140, "Setpoint Percentage Application Rate", "ppm - Parts per million", 1.0f }, + { 141, "Actual Work State", "None", 1.0f }, + { 142, "Physical Setpoint Time Latency", "ms - Time", 1.0f }, + { 143, "Physical Actual Value Time Latency", "ms - Time", 1.0f }, + { 144, "Yaw Angle", "° - Angle", 0.001f }, + { 145, "Roll Angle", "° - Angle", 0.001f }, + { 146, "Pitch Angle", "° - Angle", 0.001f }, + { 147, "Log Count", "None", 1.0f }, + { 148, "Total Fuel Consumption", "ml - Capacity large", 1.0f }, + { 149, "Instantaneous Fuel Consumption per Time", "mm³/s - Flow", 1.0f }, + { 150, "Instantaneous Fuel Consumption per Area", "mm³/m² - Capacity per area unit", 1.0f }, + { 151, "Instantaneous Area Per Time Capacity", "mm²/s - Area per time unit", 1.0f }, + { 153, "Actual Normalized Difference Vegetative Index (NDVI)", "None", 0.001f }, + { 154, "Physical Object Length", "mm - Length", 1.0f }, + { 155, "Physical Object Width", "mm - Length", 1.0f }, + { 156, "Physical Object Height", "mm - Length", 1.0f }, + { 157, "Connector Type", "None", 1.0f }, + { 158, "Prescription Control State", "None", 1.0f }, + { 159, "Number of Sub-Units per Section", "# - Quantity/Count", 1.0f }, + { 160, "Section Control State", "None", 1.0f }, + { 161, "Actual Condensed Work State (1-16)", "None", 1.0f }, + { 162, "Actual Condensed Work State (17-32)", "None", 1.0f }, + { 163, "Actual Condensed Work State (33-48)", "None", 1.0f }, + { 164, "Actual Condensed Work State (49-64)", "None", 1.0f }, + { 165, "Actual Condensed Work State (65-80)", "None", 1.0f }, + { 166, "Actual Condensed Work State (81-96)", "None", 1.0f }, + { 167, "Actual Condensed Work State (97-112)", "None", 1.0f }, + { 168, "Actual Condensed Work State (113-128)", "None", 1.0f }, + { 169, "Actual Condensed Work State (129-144)", "None", 1.0f }, + { 170, "Actual Condensed Work State (145-160)", "None", 1.0f }, + { 171, "Actual Condensed Work State (161-176)", "None", 1.0f }, + { 172, "Actual Condensed Work State (177-192)", "None", 1.0f }, + { 173, "Actual Condensed Work State (193-208)", "None", 1.0f }, + { 174, "Actual Condensed Work State (209-224)", "None", 1.0f }, + { 175, "Actual Condensed Work State (225-240)", "None", 1.0f }, + { 176, "Actual Condensed Work State (241-256)", "None", 1.0f }, + { 177, "Actual length of cut", "mm - Length", 0.001f }, + { 178, "Element Type Instance", "None", 1.0f }, + { 179, "Actual Cultural Practice", "None", 1.0f }, + { 180, "Device Reference Point (DRP) to Ground distance", "mm - Length", 1.0f }, + { 181, "Dry Mass Per Area Yield", "mg/m² - Mass per area unit", 1.0f }, + { 182, "Dry Mass Per Time Yield", "mg/s - Mass flow", 1.0f }, + { 183, "Yield Total Dry Mass", "kg - Mass", 1.0f }, + { 184, "Reference Moisture For Dry Mass", "ppm - Parts per million", 1.0f }, + { 185, "Seed Cotton Mass Per Area Yield", "mg/m² - Mass per area unit", 1.0f }, + { 186, "Lint Cotton Mass Per Area Yield", "mg/m² - Mass per area unit", 1.0f }, + { 187, "Seed Cotton Mass Per Time Yield", "mg/s - Mass flow", 1.0f }, + { 188, "Lint Cotton Mass Per Time Yield", "mg/s - Mass flow", 1.0f }, + { 189, "Yield Total Seed Cotton Mass", "kg - Mass", 1.0f }, + { 190, "Yield Total Lint Cotton Mass", "kg - Mass", 1.0f }, + { 191, "Lint Turnout Percentage", "ppm - Parts per million", 1.0f }, + { 192, "Ambient temperature", "mK - Temperature", 1.0f }, + { 193, "Setpoint Product Pressure", "Pa - Pressure", 0.1f }, + { 194, "Actual Product Pressure", "Pa - Pressure", 0.1f }, + { 195, "Minimum Product Pressure", "Pa - Pressure", 0.1f }, + { 196, "Maximum Product Pressure", "Pa - Pressure", 0.1f }, + { 197, "Setpoint Pump Output Pressure", "Pa - Pressure", 0.1f }, + { 198, "Actual Pump Output Pressure", "Pa - Pressure", 0.1f }, + { 199, "Minimum Pump Output Pressure", "Pa - Pressure", 0.1f }, + { 200, "Maximum Pump Output Pressure", "Pa - Pressure", 0.1f }, + { 201, "Setpoint Tank Agitation Pressure", "Pa - Pressure", 0.1f }, + { 202, "Actual Tank Agitation Pressure", "Pa - Pressure", 0.1f }, + { 203, "Minimum Tank Agitation Pressure", "Pa - Pressure", 0.1f }, + { 204, "Maximum Tank Agitation Pressure", "Pa - Pressure", 0.1f }, + { 205, "SC Setpoint Turn On Time", "ms - Time", 1.0f }, + { 206, "SC Setpoint Turn Off Time", "ms - Time", 1.0f }, + { 207, "Wind speed", "mm/s - Speed", 1.0f }, + { 208, "Wind direction", "° - Angle", 1.0f }, + { 209, "Relative Humidity", "% - Percent", 1.0f }, + { 210, "Sky conditions", "None", 1.0f }, + { 211, "Last Bale Flakes per Bale", "# - Quantity/Count", 1.0f }, + { 212, "Last Bale Average Moisture", "ppm - Parts per million", 1.0f }, + { 213, "Last Bale Average Strokes per Flake", "# - Quantity/Count", 1.0f }, + { 214, "Lifetime Bale Count", "# - Quantity/Count", 1.0f }, + { 215, "Lifetime Working Hours", "h - Hour", 0.05f }, + { 216, "Actual Bale Hydraulic Pressure", "Pa - Pressure", 1.0f }, + { 217, "Last Bale Average Hydraulic Pressure", "Pa - Pressure", 1.0f }, + { 218, "Setpoint Bale Compression Plunger Load", "ppm - Parts per million", 1.0f }, + { 219, "Actual Bale Compression Plunger Load", "ppm - Parts per million", 1.0f }, + { 220, "Last Bale Average Bale Compression Plunger Load", "ppm - Parts per million", 1.0f }, + { 221, "Last Bale Applied Preservative", "ml - Capacity large", 1.0f }, + { 222, "Last Bale Tag Number", "None", 1.0f }, + { 223, "Last Bale Mass", "g - Mass large", 1.0f }, + { 224, "Delta T", "mK - Temperature", 1.0f }, + { 225, "Setpoint Working Length", "mm - Length", 1.0f }, + { 226, "Actual Working Length", "mm - Length", 1.0f }, + { 227, "Minimum Working Length", "mm - Length", 1.0f }, + { 228, "Maximum Working Length", "mm - Length", 1.0f }, + { 229, "Actual Net Weight", "g - Mass large", 1.0f }, + { 230, "Net Weight State", "None", 1.0f }, + { 231, "Setpoint Net Weight", "g - Mass large", 1.0f }, + { 232, "Actual Gross Weight", "g - Mass large", 1.0f }, + { 233, "Gross Weight State", "None", 1.0f }, + { 234, "Minimum Gross Weight", "g - Mass large", 1.0f }, + { 235, "Maximum Gross Weight", "g - Mass large", 1.0f }, + { 236, "Thresher Engagement Total Time", "s - Time count", 1.0f }, + { 237, "Actual Header Working Height Status", "None", 1.0f }, + { 238, "Actual Header Rotational Speed Status", "None", 1.0f }, + { 239, "Yield Hold Status", "None", 1.0f }, + { 240, "Actual (Un)Loading System Status", "None", 1.0f }, + { 241, "Crop Temperature", "mK - Temperature", 1.0f }, + { 242, "Setpoint Sieve Clearance", "mm - Length", 1.0f }, + { 243, "Actual Sieve Clearance", "mm - Length", 1.0f }, + { 244, "Minimum Sieve Clearance", "mm - Length", 1.0f }, + { 245, "Maximum Sieve Clearance", "mm - Length", 1.0f }, + { 246, "Setpoint Chaffer Clearance", "mm - Length", 1.0f }, + { 247, "Actual Chaffer Clearance", "mm - Length", 1.0f }, + { 248, "Minimum Chaffer Clearance", "mm - Length", 1.0f }, + { 249, "Maximum Chaffer Clearance", "mm - Length", 1.0f }, + { 250, "Setpoint Concave Clearance", "mm - Length", 1.0f }, + { 251, "Actual Concave Clearance", "mm - Length", 1.0f }, + { 252, "Minimum Concave Clearance", "mm - Length", 1.0f }, + { 253, "Maximum Concave Clearance", "mm - Length", 1.0f }, + { 254, "Setpoint Separation Fan Rotational Speed", "/s - Quantity per time unit", 0.001f }, + { 255, "Actual Separation Fan Rotational Speed", "/s - Quantity per time unit", 0.001f }, + { 256, "Minimum Separation Fan Rotational Speed", "/s - Quantity per time unit", 0.001f }, + { 257, "Maximum Separation Fan Rotational Speed", "/s - Quantity per time unit", 0.001f }, + { 258, "Hydraulic Oil Temperature", "mK - Temperature", 1.0f }, + { 259, "Yield Lag Ignore Time", "ms - Time", 1.0f }, + { 260, "Yield Lead Ignore Time", "ms - Time", 1.0f }, + { 261, "Average Yield Mass Per Time", "mg/s - Mass flow", 1.0f }, + { 262, "Average Crop Moisture", "ppm - Parts per million", 1.0f }, + { 263, "Average Yield Mass Per Area", "mg/m² - Mass per area unit", 1.0f }, + { 264, "Connector Pivot X-Offset", "mm - Length", 1.0f }, + { 265, "Remaining Area", "m² - Area", 1.0f }, + { 266, "Lifetime Application Total Mass", "kg - Mass", 1.0f }, + { 267, "Lifetime Application Total Count", "# - Quantity/Count", 1.0f }, + { 268, "Lifetime Yield Total Volume", "L - Quantity per volume", 1.0f }, + { 269, "Lifetime Yield Total Mass", "kg - Mass", 1.0f }, + { 270, "Lifetime Yield Total Count", "# - Quantity/Count", 1.0f }, + { 271, "Lifetime Total Area", "m² - Area", 1.0f }, + { 272, "Lifetime Effective Total Distance", "m - Distance", 1.0f }, + { 273, "Lifetime Ineffective Total Distance", "m - Distance", 1.0f }, + { 274, "Lifetime Effective Total Time", "s - Time count", 1.0f }, + { 275, "Lifetime Ineffective Total Time", "s - Time count", 1.0f }, + { 276, "Lifetime Fuel Consumption", "L - Capacity count", 0.5f }, + { 277, "Lifetime Average Fuel Consumption per Time", "mm³/s - Flow", 1.0f }, + { 278, "Lifetime Average Fuel Consumption per Area", "mm³/m² - Capacity per area unit", 1.0f }, + { 279, "Lifetime Yield Total Dry Mass", "kg - Mass", 1.0f }, + { 280, "Lifetime Yield Total Seed Cotton Mass", "kg - Mass", 1.0f }, + { 281, "Lifetime Yield Total Lint Cotton Mass", "kg - Mass", 1.0f }, + { 282, "Lifetime Threshing Engagement Total Time", "s - Time count", 1.0f }, + { 283, "Precut Total Count", "# - Quantity/Count", 1.0f }, + { 284, "Uncut Total Count", "# - Quantity/Count", 1.0f }, + { 285, "Lifetime Precut Total Count", "# - Quantity/Count", 1.0f }, + { 286, "Lifetime Uncut Total Count", "# - Quantity/Count", 1.0f }, + { 287, "Setpoint Prescription Mode", "None", 1.0f }, + { 288, "Actual Prescription Mode", "None", 1.0f }, + { 289, "Setpoint Work State", "None", 1.0f }, + { 290, "Setpoint Condensed Work State (1-16)", "None", 1.0f }, + { 291, "Setpoint Condensed Work State (17-32)", "None", 1.0f }, + { 292, "Setpoint Condensed Work State (33-48)", "None", 1.0f }, + { 293, "Setpoint Condensed Work State (49-64)", "None", 1.0f }, + { 294, "Setpoint Condensed Work State (65-80)", "None", 1.0f }, + { 295, "Setpoint Condensed Work State (81-96)", "None", 1.0f }, + { 296, "Setpoint Condensed Work State (97-112)", "None", 1.0f }, + { 297, "Setpoint Condensed Work State (113-128)", "None", 1.0f }, + { 298, "Setpoint Condensed Work State (129-144)", "None", 1.0f }, + { 299, "Setpoint Condensed Work State (145-160)", "None", 1.0f }, + { 300, "Setpoint Condensed Work State (161-176)", "None", 1.0f }, + { 301, "Setpoint Condensed Work State (177-192)", "None", 1.0f }, + { 302, "Setpoint Condensed Work State (193-208)", "None", 1.0f }, + { 303, "Setpoint Condensed Work State (209-224)", "None", 1.0f }, + { 304, "Setpoint Condensed Work State (225-240)", "None", 1.0f }, + { 305, "Setpoint Condensed Work State (241-256)", "None", 1.0f }, + { 306, "True Rotation Point X-Offset", "mm - Length", 1.0f }, + { 307, "True Rotation Point Y-Offset", "mm - Length", 1.0f }, + { 308, "Actual Percentage Application Rate", "ppm - Parts per million", 1.0f }, + { 309, "Minimum Percentage Application Rate", "ppm - Parts per million", 1.0f }, + { 310, "Maximum Percentage Application Rate", "ppm - Parts per million", 1.0f }, + { 311, "Relative Yield Potential", "ppm - Parts per million", 1.0f }, + { 312, "Minimum Relative Yield Potential", "ppm - Parts per million", 1.0f }, + { 313, "Maximum Relative Yield Potential", "ppm - Parts per million", 1.0f }, + { 314, "Actual Percentage Crop Dry Matter", "ppm - Parts per million", 1.0f }, + { 315, "Average Percentage Crop Dry Matter", "ppm - Parts per million", 1.0f }, + { 316, "Effective Total Fuel Consumption", "ml - Capacity large", 1.0f }, + { 317, "Ineffective Total Fuel Consumption", "ml - Capacity large", 1.0f }, + { 318, "Effective Total Diesel Exhaust Fluid Consumption", "ml - Capacity large", 1.0f }, + { 319, "Ineffective Total Diesel Exhaust Fluid Consumption", "ml - Capacity large", 1.0f }, + { 320, "Last loaded Weight", "g - Mass large", 1.0f }, + { 321, "Last unloaded Weight", "g - Mass large", 1.0f }, + { 322, "Load Identification Number", "# - Quantity/Count", 1.0f }, + { 323, "Unload Identification Number", "# - Quantity/Count", 1.0f }, + { 324, "Chopper Engagement Total Time", "s - Time count", 1.0f }, + { 325, "Lifetime Application Total Volume", "L - Capacity count", 1.0f }, + { 326, "Setpoint Header Speed", "/s - Quantity per time unit", 0.001f }, + { 327, "Actual Header Speed", "/s - Quantity per time unit", 0.001f }, + { 328, "Minimum Header Speed", "/s - Quantity per time unit", 0.001f }, + { 329, "Maximum Header Speed", "/s - Quantity per time unit", 0.001f }, + { 330, "Setpoint Cutting drum speed", "/s - Quantity per time unit", 0.001f }, + { 331, "Actual Cutting drum speed", "/s - Quantity per time unit", 0.001f }, + { 332, "Minimum Cutting drum speed", "/s - Quantity per time unit", 0.001f }, + { 333, "Maximum Cutting drum speed", "/s - Quantity per time unit", 0.001f }, + { 334, "Operating Hours Since Last Sharpening", "s - Time count", 1.0f }, + { 335, "Front PTO hours", "s - Time count", 1.0f }, + { 336, "Rear PTO hours", "s - Time count", 1.0f }, + { 337, "Lifetime Front PTO hours", "h - Hour", 0.1f }, + { 338, "Lifetime Rear PTO Hours", "h - Hour", 0.1f }, + { 339, "Effective Total Loading Time", "s - Time count", 1.0f }, + { 340, "Effective Total Unloading Time", "s - Time count", 1.0f }, + { 341, "Setpoint Grain Kernel Cracker Gap", "mm - Length", 0.001f }, + { 342, "Actual Grain Kernel Cracker Gap", "mm - Length", 0.001f }, + { 343, "Minimum Grain Kernel Cracker Gap", "mm - Length", 0.001f }, + { 344, "Maximum Grain Kernel Cracker Gap", "mm - Length", 0.001f }, + { 345, "Setpoint Swathing Width", "mm - Length", 1.0f }, + { 346, "Actual Swathing Width", "mm - Length", 1.0f }, + { 347, "Minimum Swathing Width", "mm - Length", 1.0f }, + { 348, "Maximum Swathing Width", "mm - Length", 1.0f }, + { 349, "Nozzle Drift Reduction", "ppm - Parts per million", 1.0f }, + { 350, "Function or Operation Technique", "None", 1.0f }, + { 351, "Application Total Volume in [ml]", "ml - Capacity large", 1.0f }, + { 352, "Application Total Mass in gram [g]", "g - Mass large", 1.0f }, + { 353, "Total Application of Nitrogen", "g - Mass large", 1.0f }, + { 354, "Total Application of Ammonium", "g - Mass large", 1.0f }, + { 355, "Total Application of Phosphor", "g - Mass large", 1.0f }, + { 356, "Total Application of Potassium", "g - Mass large", 1.0f }, + { 357, "Total Application of Dry Matter", "kg - Mass", 1.0f }, + { 358, "Average Dry Yield Mass Per Time", "mg/s - Mass flow", 1.0f }, + { 359, "Average Dry Yield Mass Per Area", "mg/m² - Mass per area unit", 1.0f }, + { 360, "Last Bale Size", "mm - Length", 1.0f }, + { 361, "Last Bale Density", "mg/l (mass per unit volume)", 1.0f }, + { 362, "Total Bale Length", "mm - Length", 1.0f }, + { 363, "Last Bale Dry Mass", "g - Mass large", 1.0f }, + { 364, "Actual Flake Size", "mm - Length", 1.0f }, + { 365, "Setpoint Downforce Pressure", "Pa - Pressure", 1.0f }, + { 366, "Actual Downforce Pressure", "Pa - Pressure", 1.0f }, + { 367, "Condensed Section Override State (1-16)", "None", 1.0f }, + { 368, "Condensed Section Override State (17-32)", "None", 1.0f }, + { 369, "Condensed Section Override State (33-48)", "None", 1.0f }, + { 370, "Condensed Section Override State (49-64)", "None", 1.0f }, + { 371, "Condensed Section Override State (65-80)", "None", 1.0f }, + { 372, "Condensed Section Override State (81-96)", "None", 1.0f }, + { 373, "Condensed Section Override State (97-112)", "None", 1.0f }, + { 374, "Condensed Section Override State (113-128)", "None", 1.0f }, + { 375, "Condensed Section Override State (129-144)", "None", 1.0f }, + { 376, "Condensed Section Override State (145-160)", "None", 1.0f }, + { 377, "Condensed Section Override State (161-176)", "None", 1.0f }, + { 378, "Condensed Section Override State (177-192)", "None", 1.0f }, + { 379, "Condensed Section Override State (193-208)", "None", 1.0f }, + { 380, "Condensed Section Override State (209-224)", "None", 1.0f }, + { 381, "Condensed Section Override State (225-240)", "None", 1.0f }, + { 382, "Condensed Section Override State (241-256)", "None", 1.0f }, + { 383, "Apparent Wind Direction", "° - Angle", 1.0f }, + { 384, "Apparent Wind Speed", "mm/s - Speed", 1.0f }, + { 385, "MSL Atmospheric Pressure", "Pa - Pressure", 0.1f }, + { 386, "Actual Atmospheric Pressure", "Pa - Pressure", 0.1f }, + { 387, "Total Revolutions in Fractional Revolutions", "# - Quantity/Count", 0.0001f }, + { 388, "Total Revolutions in Complete Revolutions", "# - Quantity/Count", 1.0f }, + { 389, "Setpoint Revolutions specified as count per time", "r/min - Revolutions per minute", 0.0001f }, + { 390, "Actual Revolutions Per Time", "r/min - Revolutions per minute", 0.0001f }, + { 391, "Default Revolutions Per Time", "r/min - Revolutions per minute", 0.0001f }, + { 392, "Minimum Revolutions Per Time", "r/min - Revolutions per minute", 0.0001f }, + { 393, "Maximum Revolutions Per Time", "r/min - Revolutions per minute", 0.0001f }, + { 394, "Actual Fuel Tank Content", "ml - Capacity large", 1.0f }, + { 395, "Actual Diesel Exhaust Fluid Tank Content", "ml - Capacity large", 1.0f }, + { 396, "Setpoint Speed", "mm/s - Speed", 1.0f }, + { 397, "Actual Speed", "mm/s - Speed", 1.0f }, + { 398, "Minimum Speed", "mm/s - Speed", 1.0f }, + { 399, "Maximum Speed", "mm/s - Speed", 1.0f }, + { 400, "Speed Source", "None", 1.0f }, + { 401, "Actual Application of Nitrogen as [mg/l]", "mg/l - Mass per capacity unit", 1.0f }, + { 402, "Actual application of Ammonium", "mg/l - Mass per capacity unit", 1.0f }, + { 403, "Actual application of Phosphor", "mg/l - Mass per capacity unit", 1.0f }, + { 404, "Actual application of Potassium", "mg/l - Mass per capacity unit", 1.0f }, + { 405, "Actual application of Dry Matter", "mg/l - Mass per capacity unit", 1.0f }, + { 406, "Actual Protein Content", "ppm - Parts per million", 1.0f }, + { 407, "Average Protein Content", "ppm - Parts per million", 1.0f }, + { 408, "Average Crop Contamination", "ppm - Parts per million", 1.0f }, + { 409, "Total Diesel Exhaust Fluid Consumption", "ml - Capacity large", 1.0f }, + { 410, "Instantaneous Diesel Exhaust Fluid Consumption per Time", "mm³/s - Flow", 1.0f }, + { 411, "Instantaneous Diesel Exhaust Fluid Consumption per Area", "mm³/m² - Capacity per area unit", 1.0f }, + { 412, "Lifetime Diesel Exhaust Fluid Consumption", "L - Capacity count", 0.5f }, + { 413, "Lifetime Average Diesel Exhaust Fluid Consumption per Time", "mm³/s - Flow", 1.0f }, + { 414, "Lifetime Average Diesel Exhaust Fluid Consumption per Area", "mm³/m² - Capacity per area unit", 1.0f }, + { 415, "Actual Seed Singulation Percentage", "ppm - Parts per million", 1.0f }, + { 416, "Average Seed Singulation Percentage", "ppm - Parts per million", 1.0f }, + { 417, "Actual Seed Skip Percentage", "ppm - Parts per million", 1.0f }, + { 418, "Average Seed Skip Percentage", "ppm - Parts per million", 1.0f }, + { 419, "Actual Seed Multiple Percentage", "ppm - Parts per million", 1.0f }, + { 420, "Average Seed Multiple Percentage", "ppm - Parts per million", 1.0f }, + { 421, "Actual Seed Spacing Deviation", "mm - Length", 1.0f }, + { 422, "Average Seed Spacing Deviation", "mm - Length", 1.0f }, + { 423, "Actual Coefficient of Variation of Seed Spacing Percentage", "ppm - Parts per million", 1.0f }, + { 424, "Average Coefficient of Variation of Seed Spacing Percentage", "ppm - Parts per million", 1.0f }, + { 425, "Setpoint Maximum Allowed Seed Spacing Deviation", "mm - Length", 1.0f }, + { 426, "Setpoint Downforce as Force", "N - Newton", 1.0f }, + { 427, "Actual Downforce as Force", "N - Newton", 1.0f }, + { 428, "Loaded Total Mass", "kg - Mass", 1.0f }, + { 429, "Unloaded Total Mass", "kg - Mass", 1.0f }, + { 430, "Lifetime Loaded Total Mass", "kg - Mass", 1.0f }, + { 431, "Lifetime Unloaded Total Mass", "kg - Mass", 1.0f }, + { 432, "Setpoint Application Rate of Nitrogen", "mg/m² - Mass per area unit", 1.0f }, + { 433, "Actual Application Rate of Nitrogen", "mg/m² - Mass per area unit", 1.0f }, + { 434, "Minimum Application Rate of Nitrogen", "mg/m² - Mass per area unit", 1.0f }, + { 435, "Maximum Application Rate of Nitrogen", "mg/m² - Mass per area unit", 1.0f }, + { 436, "Setpoint Application Rate of Ammonium", "mg/m² - Mass per area unit", 1.0f }, + { 437, "Actual Application Rate of Ammonium", "mg/m² - Mass per area unit", 1.0f }, + { 438, "Minimum Application Rate of Ammonium", "mg/m² - Mass per area unit", 1.0f }, + { 439, "Maximum Application Rate of Ammonium", "mg/m² - Mass per area unit", 1.0f }, + { 440, "Setpoint Application Rate of Phosphor", "mg/m² - Mass per area unit", 1.0f }, + { 441, "Actual Application Rate of Phosphor", "mg/m² - Mass per area unit", 1.0f }, + { 442, "Minimum Application Rate of Phosphor", "mg/m² - Mass per area unit", 1.0f }, + { 443, "Maximum Application Rate of Phosphor", "mg/m² - Mass per area unit", 1.0f }, + { 444, "Setpoint Application Rate of Potassium", "mg/m² - Mass per area unit", 1.0f }, + { 445, "Actual Application Rate of Potassium", "mg/m² - Mass per area unit", 1.0f }, + { 446, "Minimum Application Rate of Potassium", "mg/m² - Mass per area unit", 1.0f }, + { 447, "Maximum Application Rate of Potassium", "mg/m² - Mass per area unit", 1.0f }, + { 448, "Setpoint Application Rate of Dry Matter", "ppm - Parts per million", 1.0f }, + { 449, "Actual Application Rate of Dry Matter", "ppm - Parts per million", 1.0f }, + { 450, "Minimum Application Rate of Dry Matter", "ppm - Parts per million", 1.0f }, + { 451, "Maximum Application Rate of Dry Matter", "ppm - Parts per million", 1.0f }, + { 452, "Loaded Total Volume", "ml - Capacity large", 1.0f }, + { 453, "Unloaded Total Volume", "ml - Capacity large", 1.0f }, + { 454, "Lifetime loaded Total Volume", "L - Capacity count", 1.0f }, + { 455, "Lifetime Unloaded Total Volume", "L - Capacity count", 1.0f }, + { 456, "Last loaded Volume", "ml - Capacity large", 1.0f }, + { 457, "Last unloaded Volume", "ml - Capacity large", 1.0f }, + { 458, "Loaded Total Count", "# - Quantity/Count", 1.0f }, + { 459, "Unloaded Total Count", "# - Quantity/Count", 1.0f }, + { 460, "Lifetime Loaded Total Count", "# - Quantity/Count", 1.0f }, + { 461, "Lifetime Unloaded Total Count", "# - Quantity/Count", 1.0f }, + { 462, "Last loaded Count", "# - Quantity/Count", 1.0f }, + { 463, "Last unloaded Count", "# - Quantity/Count", 1.0f }, + { 464, "Haul Counter", "# - Quantity/Count", 1.0f }, + { 465, "Lifetime Haul Counter", "# - Quantity/Count", 1.0f }, + { 466, "Actual relative connector angle", "° - Angle", 0.001f }, + { 467, "Actual Percentage Content", "% - Percent", 0.01f }, + { 468, "Soil Snow/Frozen Condtion", "None", 1.0f }, + { 469, "Estimated Soil Water Condtion", "None", 1.0f }, + { 470, "Soil Compaction", "None", 1.0f }, + { 471, "Setpoint Cultural Practice", "None", 1.0f }, + { 472, "Setpoint Length of Cut", "mm - Length", 0.001f }, + { 473, "Minimum length of cut", "mm - Length", 0.001f }, + { 474, "Maximum Length of Cut", "mm - Length", 0.001f }, + { 475, "Setpoint Bale Hydraulic Pressure", "Pa - Pressure", 1.0f }, + { 476, "Minimum Bale Hydraulic Pressure", "Pa - Pressure", 1.0f }, + { 477, "Maximum Bale Hydraulic Pressure", "Pa - Pressure", 1.0f }, + { 478, "Setpoint Flake Size", "mm - Length", 1.0f }, + { 479, "Minimum Flake Size", "mm - Length", 1.0f }, + { 480, "Maximum Flake Size", "mm - Length", 1.0f }, + { 481, "Setpoint Number of Subbales", "None", 1.0f }, + { 482, "Last Bale Number of Subbales", "None", 1.0f }, + { 483, "Setpoint Engine Speed", "r/min - Revolutions per minute", 0.0001f }, + { 484, "Actual Engine Speed", "r/min - Revolutions per minute", 0.0001f }, + { 485, "Minimum Engine Speed", "r/min - Revolutions per minute", 0.0001f }, + { 486, "Maximum Engine Speed", "r/min - Revolutions per minute", 0.0001f }, + { 488, "Diesel Exhaust Fluid Tank Percentage Level", "% - Percent", 0.01f }, + { 489, "Maximum Diesel Exhaust Fluid Tank Content", "ml - Capacity large", 1.0f }, + { 490, "Maximum Fuel Tank Content", "ml - Capacity large", 1.0f }, + { 491, "Fuel Percentage Level", "% - Percent", 0.01f }, + { 492, "Total Engine Hours", "h - Hour", 0.05f }, + { 493, "Lifetime Engine Hours", "h - Hour", 0.1f }, + { 494, "Last Event Partner ID (Byte 1-4)", "None", 1.0f }, + { 495, "Last Event Partner ID (Byte 5-8)", "None", 1.0f }, + { 496, "Last Event Partner ID (Byte 9-12)", "None", 1.0f }, + { 497, "Last Event Partner ID (Byte 13-16)", "None", 1.0f }, + { 498, "Last Event Partner ID Type", "None", 1.0f }, + { 499, "Last Event Partner ID Manufacturer ID Code", "None", 1.0f }, + { 500, "Last Event Partner ID Device Class", "None", 1.0f }, + { 501, "Setpoint Engine Torque", "% - Percent", 0.001f }, + { 502, "Actual Engine Torque", "% - Percent", 0.001f }, + { 503, "Minimum Engine Torque", "% - Percent", 0.001f }, + { 504, "Maximum Engine Torque", "% - Percent", 0.001f }, + { 505, "Tramline Control Level", "None", 1.0f }, + { 506, "Setpoint Tramline Control Level", "None", 1.0f }, + { 507, "Tramline Sequence Number", "None", 1.0f }, + { 508, "Unique A-B Guidance Reference Line ID", "None", 1.0f }, + { 509, "Actual Track Number", "None", 1.0f }, + { 510, "Track Number to the right", "None", 1.0f }, + { 511, "Track Number to the left", "None", 1.0f }, + { 512, "Guidance Line Swath Width", "mm - Length", 1.0f }, + { 513, "Guidance Line Deviation", "mm - Length", 1.0f }, + { 514, "GNSS Quality", "None", 1.0f }, + { 515, "Tramline Control State", "None", 1.0f }, + { 516, "Tramline Overdosing Rate", "ppm - Parts per million", 1.0f }, + { 517, "Setpoint Tramline Condensed Work State (1-16)", "None", 1.0f }, + { 518, "Actual Tramline Condensed Work State (1-16)", "None", 1.0f }, + { 519, "Last Bale Lifetime Count", "None", 1.0f }, + { 520, "Actual Canopy Height", "mm - Length", 1.0f }, + { 521, "GNSS Installation Type", "None", 1.0f }, + { 522, "Twine Bale Total Count", "# - Quantity/Count", 1.0f }, + { 523, "Mesh Bale Total Count", "# - Quantity/Count", 1.0f }, + { 524, "Lifetime Twine Bale Total Count", "# - Quantity/Count", 1.0f }, + { 525, "Lifetime Mesh Bale Total Count", "# - Quantity/Count", 1.0f }, + { 526, "Actual Cooling Fluid Temperature", "mK - Temperature", 1.0f }, + { 528, "Last Bale Capacity", "kg/h - Mass per hour unit", 1.0f }, + { 529, "Setpoint Tillage Disc Gang Angle", "° - Angle", 0.001f }, + { 530, "Actual Tillage Disc Gang Angle", "° - Angle", 0.001f }, + { 531, "Actual Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 532, "Setpoint Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 533, "Default Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 534, "Minimum Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 535, "Maximum Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 536, "Total Applied Preservative", "ml - Capacity large", 1.0f }, + { 537, "Lifetime Applied Preservative", "ml - Capacity large", 1.0f }, + { 538, "Average Applied Preservative Per Yield Mass", "mm³/kg - Capacity per mass unit", 1.0f }, + { 539, "Actual Preservative Tank Volume", "ml - Capacity large", 1.0f }, + { 540, "Actual Preservative Tank Level", "ppm - Parts per million", 1.0f }, + { 541, "Actual PTO Speed", "r/min - Revolutions per minute", 0.0001f }, + { 542, "Setpoint PTO Speed", "r/min - Revolutions per minute", 0.0001f }, + { 543, "Default PTO Speed", "r/min - Revolutions per minute", 0.0001f }, + { 544, "Minimum PTO Speed", "r/min - Revolutions per minute", 0.0001f }, + { 545, "Maximum PTO Speed", "r/min - Revolutions per minute", 0.0001f }, + { 546, "Lifetime Chopping Engagement Total Time", "s - Time count", 1.0f }, + { 547, "Setpoint Bale Compression Plunger Load (N)", "N - Newton", 1.0f }, + { 548, "Actual Bale Compression Plunger Load (N)", "N - Newton", 1.0f }, + { 549, "Last Bale Average Bale Compression Plunger Load (N)", "N - Newton", 1.0f }, + { 550, "Ground Cover", "% - Percent", 0.1f }, + { 551, "Actual PTO Torque", "N*m - Newton metre", 0.0001f }, + { 552, "Setpoint PTO Torque", "N*m - Newton metre", 0.0001f }, + { 553, "Default PTO Torque", "N*m - Newton metre", 0.0001f }, + { 554, "Minimum PTO Torque", "N*m - Newton metre", 0.0001f }, + { 555, "Maximum PTO Torque", "N*m - Newton metre", 0.0001f }, + { 556, "Present Weather Conditions", "None", 1.0f }, + { 557, "Setpoint Electrical Current", "A - Electrical current", 0.005f }, + { 558, "Actual Electrical Current", "A - Electrical current", 0.005f }, + { 559, "Minimum Electrical Current", "A - Electrical current", 0.005f }, + { 560, "Maximum Electrical Current", "A - Electrical current", 0.005f }, + { 561, "Default Electrical Current", "A - Electrical current", 0.005f }, + { 562, "Setpoint Voltage", "V - Electrical voltage", 0.001f }, + { 563, "Default Voltage", "V - Electrical voltage", 0.001f }, + { 564, "Actual Voltage", "V - Electrical voltage", 0.001f }, + { 565, "Minimum Voltage", "V - Electrical voltage", 0.001f }, + { 566, "Maximum Voltage", "V - Electrical voltage", 0.001f }, + { 567, "Actual Electrical Resistance", "Ohm - Electrical resistance", 0.01f }, + { 568, "Setpoint Electrical Power", "W - Electrical Power", 0.001f }, + { 569, "Actual Electrical Power", "W - Electrical Power", 0.001f }, + { 570, "Default Electrical Power", "W - Electrical Power", 0.001f }, + { 571, "Maximum Electrical Power", "W - Electrical Power", 0.001f }, + { 572, "Minimum Electrical Power", "W - Electrical Power", 0.001f }, + { 573, "Total Electrical Energy", "kWh - Electrical energy", 0.001f }, + { 574, "Setpoint Electrical Energy per Area Application Rate", "kWh/m² - Electrical energy per area", 1.0E-7f }, + { 575, "Actual Electrical Energy per Area Application Rate", "kWh/m² - Electrical energy per area", 1.0E-7f }, + { 576, "Maximum Electrical Energy per Area Application Rate", "kWh/m² - Electrical energy per area", 1.0E-7f }, + { 577, "Minimum Electrical Energy per Area Application Rate", "kWh/m² - Electrical energy per area", 1.0E-7f }, + { 578, "Setpoint Temperature", "mK - Temperature", 1.0f }, + { 579, "Actual Temperature", "mK - Temperature", 1.0f }, + { 580, "Minimum Temperature", "mK - Temperature", 1.0f }, + { 581, "Maximum Temperature", "mK - Temperature", 1.0f }, + { 582, "Default Temperature", "mK - Temperature", 1.0f }, + { 583, "Setpoint Frequency", "Hz - Electrical frequency", 0.001f }, + { 584, "Actual Frequency", "Hz - Electrical frequency", 0.001f }, + { 585, "Minimum Frequency", "Hz - Electrical frequency", 0.001f }, + { 586, "Maximum Frequency", "Hz - Electrical frequency", 0.001f }, + { 587, "Previous Rainfall", "None", 1.0f }, + { 588, "Setpoint Volume Per Area Application Rate as [ml/m²]", "ml/m² - Capacity per area large", 0.1f }, + { 589, "Actual Volume Per Area Application Rate as [ml/m²]", "ml/m² - Capacity per area large", 0.1f }, + { 590, "Minimum Volume Per Area Application Rate as [ml/m²]", "ml/m² - Capacity per area large", 0.1f }, + { 591, "Maximum Volume Per Area Application Rate as [ml/m²]", "ml/m² - Capacity per area large", 0.1f }, + { 592, "Default Volume Per Area Application Rate as [ml/m²]", "ml/m² - Capacity per area large", 0.1f }, + { 593, "Traction Type", "None", 1.0f }, + { 594, "Steering Type", "None", 1.0f }, + { 595, "Machine Mode", "None", 1.0f }, + { 596, "Cargo Area Cover State", "% - Percent", 1.0f }, + { 597, "Total Distance", "mm - Length", 1.0f }, + { 598, "Lifetime Total Distance", "m - Distance", 1.0f }, + { 599, "Total Distance Field", "mm - Length", 1.0f }, + { 600, "Lifetime Total Distance Field", "m - Distance", 1.0f }, + { 601, "Total Distance Street", "mm - Length", 1.0f }, + { 602, "Lifetime Total Distance Street", "m - Distance", 1.0f }, + { 603, "Actual Tramline Condensed Work State (17-32)", "None", 1.0f }, + { 604, "Actual Tramline Condensed Work State (33-48)", "None", 1.0f }, + { 605, "Actual Tramline Condensed Work State (49-64)", "None", 1.0f }, + { 606, "Actual Tramline Condensed Work State (65-80)", "None", 1.0f }, + { 607, "Actual Tramline Condensed Work State (81-96)", "None", 1.0f }, + { 608, "Actual Tramline Condensed Work State (97-112)", "None", 1.0f }, + { 609, "Actual Tramline Condensed Work State (113-128)", "None", 1.0f }, + { 610, "Actual Tramline Condensed Work State (129-144)", "None", 1.0f }, + { 611, "Actual Tramline Condensed Work State (145-160)", "None", 1.0f }, + { 612, "Actual Tramline Condensed Work State (161-176)", "None", 1.0f }, + { 613, "Actual Tramline Condensed Work State (177-192)", "None", 1.0f }, + { 614, "Actual Tramline Condensed Work State (193-208)", "None", 1.0f }, + { 615, "Actual Tramline Condensed Work State (209-224)", "None", 1.0f }, + { 616, "Actual Tramline Condensed Work State (225-240)", "None", 1.0f }, + { 617, "Actual Tramline Condensed Work State (241-256)", "None", 1.0f }, + { 618, "Setpoint Tramline Condensed Work State (17-32)", "None", 1.0f }, + { 619, "Setpoint Tramline Condensed Work State (33-48)", "None", 1.0f }, + { 620, "Setpoint Tramline Condensed Work State (49-64)", "None", 1.0f }, + { 621, "Setpoint Tramline Condensed Work State (65-80)", "None", 1.0f }, + { 622, "Setpoint Tramline Condensed Work State (81-96)", "None", 1.0f }, + { 623, "Setpoint Tramline Condensed Work State (97-112)", "None", 1.0f }, + { 624, "Setpoint Tramline Condensed Work State (113-128)", "None", 1.0f }, + { 625, "Setpoint Tramline Condensed Work State (129-144)", "None", 1.0f }, + { 626, "Setpoint Tramline Condensed Work State (145-160)", "None", 1.0f }, + { 627, "Setpoint Tramline Condensed Work State (161-176)", "None", 1.0f }, + { 628, "Setpoint Tramline Condensed Work State (177-192)", "None", 1.0f }, + { 629, "Setpoint Tramline Condensed Work State (193-208)", "None", 1.0f }, + { 630, "Setpoint Tramline Condensed Work State (209-224)", "None", 1.0f }, + { 631, "Setpoint Tramline Condensed Work State (225-240)", "None", 1.0f }, + { 632, "Setpoint Tramline Condensed Work State (241-256)", "None", 1.0f }, + { 633, "Setpoint Volume per distance Application Rate", "ml/m - Volume per distance", 0.001f }, + { 634, "Actual Volume per distance Application Rate", "ml/m - Volume per distance", 0.001f }, + { 635, "Default Volume per distance Application Rate", "ml/m - Volume per distance", 0.001f }, + { 636, "Minimum Volume per distance Application Rate", "ml/m - Volume per distance", 0.001f }, + { 637, "Maximum Volume per distance Application Rate", "ml/m - Volume per distance", 0.001f }, + { 638, "Setpoint Tire Pressure", "Pa - Pressure", 0.1f }, + { 639, "Actual Tire Pressure", "Pa - Pressure", 0.1f }, + { 640, "Default Tire Pressure", "Pa - Pressure", 0.1f }, + { 641, "Minimum Tire Pressure", "Pa - Pressure", 0.1f }, + { 642, "Maximum Tire Pressure", "Pa - Pressure", 0.1f }, + { 643, "Actual Tire Temperature", "mK - Temperature", 1.0f }, + { 644, "Binding Method", "None", 1.0f }, + { 645, "Last Bale Number of Knives", "# - Quantity/Count", 1.0f }, + { 646, "Last Bale Binding Twine Consumption", "mm - Length", 1.0f }, + { 647, "Last Bale Binding Mesh Consumption", "mm - Length", 1.0f }, + { 648, "Last Bale Binding Film Consumption", "mm - Length", 1.0f }, + { 649, "Last Bale Binding Film Stretching", "% - Percent", 0.001f }, + { 650, "Last Bale Wrapping Film Width", "mm - Length", 1.0f }, + { 651, "Last Bale Wrapping Film Consumption", "mm - Length", 1.0f }, + { 652, "Last Bale Wrapping Film Stretching", "% - Percent", 0.001f }, + { 653, "Last Bale Wrapping Film Overlap Percentage", "% - Percent", 0.001f }, + { 654, "Last Bale Wrapping Film Layers", "# - Quantity/Count", 1.0f }, + { 655, "Electrical Apparent Soil Conductivity", "mS/m - Milli Siemens per meter", 0.1f }, + { 656, "SC Actual Turn On Time", "None", 1.0f }, + { 657, "SC Actual Turn Off Time", "None", 1.0f }, + { 658, "Actual CO2 equivalent specified as mass per area", "mg/m² - Mass per area unit", 1.0f }, + { 659, "Actual CO2 equivalent specified as mass per time", "mg/s - Mass flow", 1.0f }, + { 660, "Actual CO2 equivalent specified as mass per mass", "mg/kg - Mass per mass unit", 1.0f }, + { 661, "Actual CO2 equivalent specified as mass per yield", "mg/kg - Mass per mass unit", 1.0f }, + { 662, "Actual CO2 equivalent specified as mass per volume", "mg/l - Mass per capacity unit", 1.0f }, + { 663, "Actual CO2 equivalent specified as mass per count", "None", 1.0f }, + { 664, "Total CO2 equivalent", "kg - Mass", 1.0f }, + { 665, "Lifetime total CO2 equivalent", "kg - Mass", 1.0f }, + { 666, "Working Direction", "None", 1.0f }, + { 667, "Distance between Guidance Track Number 0R and 1", "mm - Length", 1.0f }, + { 668, "Distance between Guidance Track Number 0R and 0L", "mm - Length", 1.0f }, + { 669, "Bout Track Number Shift", "None", 1.0f }, + { 670, "Tramline Crop protection/fertilization Working Width", "mm - Length", 1.0f }, + { 671, "Tramline Tire Width", "mm - Length", 1.0f }, + { 672, "Tramline Wheel Distance", "mm - Length", 1.0f }, + { 673, "Tramline Irrigation Working Width", "mm - Length", 1.0f }, + { 674, "Tramline Irrigation Tire Width", "mm - Length", 1.0f }, + { 675, "Tramline Irrigation Wheel Distance", "mm - Length", 1.0f }, + { 676, "Last Bale Binding Mesh Layers", "# - Quantity/Count", 1.0f }, + { 677, "Last Bale Binding Film Layers", "# - Quantity/Count", 1.0f }, + { 678, "Last Bale Binding Twine Layers", "# - Quantity/Count", 1.0f }, + { 679, "Crop Contamination Total Mass", "kg - Mass", 1.0f }, + { 680, "Crop Contamination Lifetime Total Mass", "kg - Mass", 1.0f }, + { 681, "Film bale Total Count", "# - Quantity/Count", 1.0f }, + { 682, "Mesh bale Total Count", "# - Quantity/Count", 1.0f }, + { 683, "Twine bale Total Count", "# - Quantity/Count", 1.0f }, + { 684, "Wrapping Film bale Total Count", "# - Quantity/Count", 1.0f }, + { 685, "Lifetime Film Bale Total Count", "# - Quantity/Count", 1.0f }, + { 686, "Lifetime Mesh Bale Total Count", "# - Quantity/Count", 1.0f }, + { 687, "Lifetime Twine Bale Total Count", "# - Quantity/Count", 1.0f }, + { 688, "Lifetime Wrapping Film Bale Total Count", "# - Quantity/Count", 1.0f }, + { 32768, "Maximum Droplet Size", "None", 1.0f }, + { 32769, "Maximum Crop Grade Diameter", "mm - Length", 0.001f }, + { 32770, "Maximum Crop Grade Length", "mm - Length", 0.001f }, + { 32771, "Maximum Crop Contamination Mass per Area", "mg/m² - Mass per area unit", 1.0f }, + { 32772, "Maximum Crop Contamination Mass per Time", "mg/s - Mass flow", 1.0f }, + { 36864, "Minimum Droplet Size", "None", 1.0f }, + { 36865, "Minimum Crop Grade Diameter", "mm - Length", 0.001f }, + { 36866, "Minimum Crop Grade Length", "mm - Length", 0.001f }, + { 36867, "Minimum Crop Contamination Mass per Area", "mg/m² - Mass per area unit", 1.0f }, + { 36868, "Minimum Crop Contamination Mass per Time", "mg/s - Mass flow", 1.0f }, + { 40960, "Default Droplet Size", "None", 1.0f }, + { 40961, "Default Crop Grade Diameter", "mm - Length", 0.001f }, + { 40962, "Default Crop Grade Length", "mm - Length", 0.001f }, + { 40963, "Default Crop Contamination Mass per Area", "mg/m² - Mass per area unit", 1.0f }, + { 40964, "Default Crop Contamination Mass per Time", "mg/s - Mass flow", 1.0f }, + { 45056, "Actual Droplet Size", "None", 1.0f }, + { 45057, "Actual Crop Grade Diameter", "mm - Length", 0.001f }, + { 45058, "Actual Crop Grade Length", "mm - Length", 0.001f }, + { 45059, "Actual Crop Contamination Mass per Area", "mg/m² - Mass per area unit", 1.0f }, + { 45060, "Actual Crop Contamination Mass per Time", "mg/s - Mass flow", 1.0f }, + { 49152, "Setpoint Droplet Size", "None", 1.0f }, + { 49153, "Setpoint Crop Grade Diameter", "mm - Length", 0.001f }, + { 49154, "Setpoint Crop Grade Length", "mm - Length", 0.001f }, + { 49155, "Setpoint Crop Contamination Mass per Area", "mg/m² - Mass per area unit", 1.0f }, + { 49156, "Setpoint Crop Contamination Mass per Time", "mg/s - Mass flow", 1.0f }, + { 57342, "PGN Based Data", "None", 1.0f }, + { 57343, "Request Default Process Data", "None", 1.0f }, + { 57344, "65534 Proprietary DDI Range", "None", 0.0f }, + { 65535, "Reserved", "None", 0.0f }, + }; + +} // namespace isobus diff --git a/src/isobus_data_dictionary.hpp b/src/isobus_data_dictionary.hpp new file mode 100644 index 0000000..5fb1100 --- /dev/null +++ b/src/isobus_data_dictionary.hpp @@ -0,0 +1,45 @@ +//================================================================================================ +/// @file isobus_data_dictionary.hpp +/// +/// @brief This file contains the definition of an auto-generated lookup of all ISOBUS DDIs +/// as defined in ISO11783-11, exported from isobus.net. +/// This file was generated January 25, 2024. +/// +/// @author Adrian Del Grosso +/// @copyright 2024 The Open-Agriculture Developers +//================================================================================================ +#ifndef ISOBUS_DATA_DICTIONARY_HPP +#define ISOBUS_DATA_DICTIONARY_HPP + +#include +#include + +namespace isobus +{ + /// @brief This class contains the definition of an auto-generated lookup of all ISOBUS DDIs + class DataDictionary + { + public: + /// @brief A struct containing the information for a single DDI + struct Entry + { + const std::uint16_t ddi; ///< The DDI number + + const std::string name; ///< The name of the DDI + const std::string units; ///< The units of the DDI + const float resolution; ///< The resolution of the DDI + }; + + /// @brief Checks the ISO 11783-11 database for the given DDI number + /// and returns the corresponding entry if found. + /// @param dataDictionaryIdentifier The DDI number to look up + /// @return The entry for the given DDI number, or a default entry if not found + static const Entry &get_entry(std::uint16_t dataDictionaryIdentifier); + + private: + static const Entry DDI_ENTRIES[715]; ///< A lookup table of all DDI entries in ISO11783-11 + static const Entry DEFAULT_ENTRY; ///< A default "unknown" DDI to return if a DDI is not in the database + }; +} // namespace isobus + +#endif // ISOBUS_DATA_DICTIONARY_HPP diff --git a/src/isobus_device_descriptor_object_pool.cpp b/src/isobus_device_descriptor_object_pool.cpp index 64add91..2223f0b 100644 --- a/src/isobus_device_descriptor_object_pool.cpp +++ b/src/isobus_device_descriptor_object_pool.cpp @@ -8,6 +8,7 @@ //================================================================================================ #include "isobus_device_descriptor_object_pool.hpp" +#include "can_constants.hpp" #include "can_stack_logger.hpp" #include "platform_endianness.hpp" #include "to_string.hpp" @@ -15,6 +16,8 @@ #include #include #include +#include +#include namespace isobus { @@ -801,6 +804,184 @@ namespace isobus return retVal; } + bool DeviceDescriptorObjectPool::generate_task_data_iso_xml(std::string &resultantString) + { + bool retVal = true; + + resultantString.clear(); + + if (taskControllerCompatibilityLevel > MAX_TC_VERSION_SUPPORTED) + { + CANStackLogger::warn("[DDOP]: An XML DDOP is being generated for a TC version that is unsupported. This may cause issues."); + } + + if (resolve_parent_ids_to_objects()) + { + std::ostringstream xmlOutput; + std::ios initialStreamFormat(NULL); + std::size_t numberOfDevices = 1; + std::size_t numberOfElements = 1; + initialStreamFormat.copyfmt(xmlOutput); + retVal = true; + + xmlOutput << "" << std::endl; + xmlOutput << "" << std::endl; + + // Find the device object, which will be the first object written + for (std::size_t i = 0; i < size(); i++) + { + auto currentObject = get_object_by_index(static_cast(i)); + + if ((nullptr != currentObject) && + (task_controller_object::ObjectTypes::Device == currentObject->get_object_type())) + { + // Found device + auto rootDevice = std::static_pointer_cast(currentObject); + xmlOutput << "(numberOfDevices); + numberOfDevices++; + xmlOutput << "\" B=\"" << rootDevice->get_designator(); + xmlOutput << "\" C=\"" << rootDevice->get_software_version(); + xmlOutput << "\" D=\"" << std::uppercase << std::hex << std::setfill('0') << std::setw(16) << static_cast(rootDevice->get_iso_name()); + xmlOutput.copyfmt(initialStreamFormat); + xmlOutput << "\" E=\"" << rootDevice->get_serial_number(); + xmlOutput << "\" F=\""; + + auto lStructureLabel = rootDevice->get_structure_label(); + for (std::uint8_t j = 0; j < 7; j++) + { + std::uint8_t structureByte = static_cast(lStructureLabel.at(6 - j)); + xmlOutput << std::uppercase << std::hex << std::setfill('0') << std::setw(2) << static_cast(structureByte); + } + + xmlOutput << "\" G=\""; + + for (std::uint_fast8_t j = 0; j < 7; j++) + { + xmlOutput << std::uppercase << std::hex << std::setfill('0') << std::setw(2) << static_cast(rootDevice->get_localization_label().at(6 - j)); + } + xmlOutput.copyfmt(initialStreamFormat); + xmlOutput << "\">" << std::endl; + + // Next, process all elements + for (std::size_t j = 0; j < this->size(); j++) + { + auto currentSubObject = get_object_by_index(static_cast(j)); + + if ((nullptr != currentSubObject) && + (task_controller_object::ObjectTypes::DeviceElement == currentSubObject->get_object_type())) + { + auto deviceElement = std::static_pointer_cast(currentSubObject); + + xmlOutput << "\t(numberOfElements); + numberOfElements++; + xmlOutput << "\" B=\"" << static_cast(deviceElement->get_object_id()); + xmlOutput << "\" C=\"" << static_cast(deviceElement->get_type()); + xmlOutput << "\" D=\"" << deviceElement->get_designator(); + xmlOutput << "\" E=\"" << static_cast(deviceElement->get_element_number()); + xmlOutput << "\" F=\"" << static_cast(deviceElement->get_parent_object()); + + if (deviceElement->get_number_child_objects() > 0) + { + xmlOutput << "\">" << std::endl; + + // Process a list of all device object references + for (std::size_t k = 0; k < deviceElement->get_number_child_objects(); k++) + { + xmlOutput << "\t\t(deviceElement->get_child_object_id(k)) << "\"/>" << std::endl; + } + xmlOutput << "\t" << std::endl; + } + else + { + xmlOutput << "\"/>" << std::endl; + } + } + } + + // Next, process all DPDs + for (std::size_t j = 0; j < this->size(); j++) + { + auto currentSubObject = get_object_by_index(static_cast(j)); + + if ((nullptr != currentSubObject) && + (task_controller_object::ObjectTypes::DeviceProcessData == currentSubObject->get_object_type())) + { + auto deviceProcessData = std::static_pointer_cast(currentSubObject); + + xmlOutput << "\t(deviceProcessData->get_object_id()); + xmlOutput << "\" B=\"" << std::uppercase << std::hex << std::setfill('0') << std::setw(4) << static_cast(deviceProcessData->get_ddi()); + xmlOutput.copyfmt(initialStreamFormat); + xmlOutput << "\" C=\"" << static_cast(deviceProcessData->get_properties_bitfield()); + xmlOutput << "\" D=\"" << static_cast(deviceProcessData->get_trigger_methods_bitfield()); + xmlOutput << "\" E=\"" << deviceProcessData->get_designator(); + if (0xFFFF != deviceProcessData->get_device_value_presentation_object_id()) + { + xmlOutput << "\" F=\"" << static_cast(deviceProcessData->get_device_value_presentation_object_id()); + } + xmlOutput << "\"/>" << std::endl; + } + } + + // Next, process all child DPTs + for (std::size_t j = 0; j < this->size(); j++) + { + auto currentSubObject = get_object_by_index(static_cast(j)); + + if ((nullptr != currentSubObject) && + (task_controller_object::ObjectTypes::DeviceProperty == currentSubObject->get_object_type())) + { + auto deviceProperty = std::static_pointer_cast(currentSubObject); + + xmlOutput << "\t(deviceProperty->get_object_id()); + xmlOutput << "\" B=\"" << std::uppercase << std::hex << std::setfill('0') << std::setw(4) << static_cast(deviceProperty->get_ddi()); + xmlOutput.copyfmt(initialStreamFormat); + xmlOutput << "\" C=\"" << static_cast(deviceProperty->get_value()); + xmlOutput << "\" D=\"" << deviceProperty->get_designator(); + if (0xFFFF != deviceProperty->get_device_value_presentation_object_id()) + { + xmlOutput << "\" E=\"" << static_cast(deviceProperty->get_device_value_presentation_object_id()); + } + xmlOutput << "\"/>" << std::endl; + } + } + + // Next, process all child DVPs + for (std::size_t j = 0; j < this->size(); j++) + { + auto currentSubObject = get_object_by_index(static_cast(j)); + + if ((nullptr != currentSubObject) && + (task_controller_object::ObjectTypes::DeviceValuePresentation == currentSubObject->get_object_type())) + { + auto deviceValuePresentation = std::static_pointer_cast(currentSubObject); + + xmlOutput << "\t(deviceValuePresentation->get_object_id()); + xmlOutput << "\" B=\"" << static_cast(deviceValuePresentation->get_offset()); + xmlOutput << "\" C=\"" << std::fixed << std::setprecision(6) << deviceValuePresentation->get_scale(); + xmlOutput.copyfmt(initialStreamFormat); + xmlOutput << "\" D=\"" << static_cast(deviceValuePresentation->get_number_of_decimals()); + xmlOutput << "\" E=\"" << deviceValuePresentation->get_designator(); + xmlOutput << "\"/>" << std::endl; + } + } + + // Close DVC object + xmlOutput << "" << std::endl; + xmlOutput << "" << std::endl; + resultantString = xmlOutput.str(); + CANStackLogger::debug("[DDOP]: Generated ISO XML DDOP data OK"); + break; + } + } + } + else + { + CANStackLogger::error("[DDOP]: Failed to resolve all object IDs in DDOP. Your DDOP contains invalid object references."); + retVal = false; + } + return retVal; + } + std::shared_ptr DeviceDescriptorObjectPool::get_object_by_id(std::uint16_t objectID) { std::shared_ptr retVal; @@ -890,7 +1071,7 @@ namespace isobus { // Process parent object auto currentDeviceElement = reinterpret_cast(currentObject.get()); - if (task_controller_object::Object::NULL_OBJECT_ID != currentDeviceElement->get_parent_object()) + if (NULL_OBJECT_ID != currentDeviceElement->get_parent_object()) { auto parent = get_object_by_id(currentDeviceElement->get_parent_object()); if (nullptr != parent.get()) @@ -963,7 +1144,7 @@ namespace isobus { auto currentProcessData = reinterpret_cast(currentObject.get()); - if (task_controller_object::Object::NULL_OBJECT_ID != currentProcessData->get_device_value_presentation_object_id()) + if (NULL_OBJECT_ID != currentProcessData->get_device_value_presentation_object_id()) { auto child = get_object_by_id(currentProcessData->get_device_value_presentation_object_id()); if (nullptr == child.get()) @@ -991,7 +1172,7 @@ namespace isobus { auto currentProperty = reinterpret_cast(currentObject.get()); - if (task_controller_object::Object::NULL_OBJECT_ID != currentProperty->get_device_value_presentation_object_id()) + if (NULL_OBJECT_ID != currentProperty->get_device_value_presentation_object_id()) { auto child = get_object_by_id(currentProperty->get_device_value_presentation_object_id()); if (nullptr == child.get()) @@ -1034,7 +1215,7 @@ namespace isobus { bool retVal = true; - if ((0 != uniqueID) && (task_controller_object::Object::NULL_OBJECT_ID != uniqueID)) + if ((0 != uniqueID) && (NULL_OBJECT_ID != uniqueID)) { for (auto ¤tObject : objectList) { diff --git a/src/isobus_device_descriptor_object_pool.hpp b/src/isobus_device_descriptor_object_pool.hpp index e2257bb..f48178c 100644 --- a/src/isobus_device_descriptor_object_pool.hpp +++ b/src/isobus_device_descriptor_object_pool.hpp @@ -135,11 +135,18 @@ namespace isobus /// @returns `true` if the object pool was generated and is valid, otherwise `false`. bool generate_binary_object_pool(std::vector &resultantPool); + /// Constructs a ISOXML formatted TASKDATA.xml file inside a string using the objects that were previously added. + /// @param[in,out] resultantString The XML representation of the DDOP, or an empty string if this function returns false + /// @returns `true` if the object pool was generated and is valid, otherwise `false`. + bool generate_task_data_iso_xml(std::string &resultantString); + /// @brief Gets an object from the DDOP that corresponds to a certain object ID + /// @param[in] objectID The ID of the object to get /// @returns Pointer to the object matching the provided ID, or nullptr if no match was found std::shared_ptr get_object_by_id(std::uint16_t objectID); /// @brief Gets an object from the DDOP by index based on object creation + /// @param[in] index The index of the object to get /// @returns Pointer to the object matching the index, or nullptr if no match was found std::shared_ptr get_object_by_index(std::uint16_t index); diff --git a/src/isobus_diagnostic_protocol.cpp b/src/isobus_diagnostic_protocol.cpp index 8992b8f..11c37dc 100644 --- a/src/isobus_diagnostic_protocol.cpp +++ b/src/isobus_diagnostic_protocol.cpp @@ -149,7 +149,7 @@ namespace isobus CANNetworkManager::CANNetwork.remove_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::DiagnosticMessage22), process_message, this); CANNetworkManager::CANNetwork.remove_protocol_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::DiagnosticMessage13), process_message, this); CANNetworkManager::CANNetwork.remove_global_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::DiagnosticMessage13), process_message, this); - addressViolationEventHandle.reset(); + CANNetworkManager::CANNetwork.get_address_violation_event_dispatcher().remove_listener(addressViolationEventHandle); } } diff --git a/src/isobus_diagnostic_protocol.hpp b/src/isobus_diagnostic_protocol.hpp index 93251df..5430dd7 100644 --- a/src/isobus_diagnostic_protocol.hpp +++ b/src/isobus_diagnostic_protocol.hpp @@ -204,7 +204,7 @@ namespace isobus FailureModeIdentifier get_failure_mode_identifier() const; private: - friend class DiagnosticProtocol; + friend class DiagnosticProtocol; ///< Allows the protocol to set the occurrence count std::uint32_t suspectParameterNumber = 0xFFFFFFFF; ///< This 19-bit number is used to identify the item for which diagnostics are being reported FailureModeIdentifier failureModeIdentifier = FailureModeIdentifier::ConditionExists; ///< The FMI defines the type of failure detected in the sub-system identified by an SPN LampStatus lampState = LampStatus::None; ///< The J1939 lamp state for this DTC @@ -221,6 +221,7 @@ namespace isobus ~DiagnosticProtocol(); /// @brief The protocol's initializer function + /// @returns true if the protocol was initialized, false if it was already initialized bool initialize(); /// @brief Returns if the protocol has been initialized @@ -490,7 +491,7 @@ namespace isobus static void process_flags(std::uint32_t flag, void *parentPointer); std::shared_ptr myControlFunction; ///< The internal control function that this protocol will send from - std::shared_ptr addressViolationEventHandle; ///< Stores the handle from registering for address violation events + EventCallbackHandle addressViolationEventHandle; ///< Stores the handle from registering for address violation events NetworkType networkType; ///< The diagnostic network type that this protocol will use std::vector activeDTCList; ///< Keeps track of all the active DTCs std::vector inactiveDTCList; ///< Keeps track of all the previously active DTCs diff --git a/src/isobus_functionalities.hpp b/src/isobus_functionalities.hpp index 38a84ee..e200796 100644 --- a/src/isobus_functionalities.hpp +++ b/src/isobus_functionalities.hpp @@ -455,6 +455,7 @@ namespace isobus /// @param[out] acknowledge Tells the PGN request protocol to ACK ack the request /// @param[out] acknowledgeType Tells the PGN request protocol what kind of ACK to use /// @param[in] parentPointer A generic context variable, usually the "this" pointer of the registrant for callbacks + /// @returns true if the PGN was handled, otherwise false static bool pgn_request_handler(std::uint32_t parameterGroupNumber, std::shared_ptr requestingControlFunction, bool &acknowledge, diff --git a/src/isobus_guidance_interface.cpp b/src/isobus_guidance_interface.cpp index f1a959d..6519a98 100644 --- a/src/isobus_guidance_interface.cpp +++ b/src/isobus_guidance_interface.cpp @@ -344,7 +344,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(guidanceSystemCommandTransmitData.get_sender_control_function()), destinationControlFunction, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } @@ -393,7 +393,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(guidanceMachineInfoTransmitData.get_sender_control_function()), destinationControlFunction, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } diff --git a/src/isobus_guidance_interface.hpp b/src/isobus_guidance_interface.hpp index 5772fff..24d9c5b 100644 --- a/src/isobus_guidance_interface.hpp +++ b/src/isobus_guidance_interface.hpp @@ -262,6 +262,7 @@ namespace isobus /// @brief Sets the exit code for the guidance system /// @details This parameter is used to indicate why the guidance system cannot currently accept /// remote commands or has most recently stopped accepting remote commands. + /// @param[in] exitCode The exit code for the guidance system to report /// @returns The exit code for the guidance system bool set_guidance_system_command_exit_reason_code(std::uint8_t exitCode); @@ -334,6 +335,7 @@ namespace isobus /// @param[in] index An index of senders of the agricultural guidance machine info message /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. + /// @returns The content of the agricultural guidance machine info message std::shared_ptr get_received_guidance_machine_info(std::size_t index); /// @brief Returns the content of the agricultural guidance curvature command message @@ -341,6 +343,7 @@ namespace isobus /// @param[in] index An index of senders of the agricultural guidance curvature command message /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. + /// @returns The content of the agricultural guidance curvature command message std::shared_ptr get_received_guidance_system_command(std::size_t index); /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated guidance machine info messages are received. @@ -402,4 +405,4 @@ namespace isobus }; } // namespace isobus -#endif // ISOBUS_GUIDANCE_HPP \ No newline at end of file +#endif // ISOBUS_GUIDANCE_HPP diff --git a/src/isobus_language_command_interface.cpp b/src/isobus_language_command_interface.cpp index beca8f0..a61e1a0 100644 --- a/src/isobus_language_command_interface.cpp +++ b/src/isobus_language_command_interface.cpp @@ -21,9 +21,10 @@ namespace isobus { - LanguageCommandInterface::LanguageCommandInterface(std::shared_ptr sourceControlFunction) : + LanguageCommandInterface::LanguageCommandInterface(std::shared_ptr sourceControlFunction, bool shouldRespondToRequests) : myControlFunction(sourceControlFunction), - myPartner(nullptr) + myPartner(nullptr), + respondToRequests(shouldRespondToRequests) { } @@ -38,6 +39,11 @@ namespace isobus if (initialized) { CANNetworkManager::CANNetwork.remove_global_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::LanguageCommand), process_rx_message, this); + + if (respondToRequests && (!myControlFunction->get_pgn_request_protocol().expired())) + { + myControlFunction->get_pgn_request_protocol().lock()->remove_pgn_request_callback(static_cast(CANLibParameterGroupNumber::LanguageCommand), on_language_request, this); + } } } @@ -48,6 +54,11 @@ namespace isobus if (nullptr != myControlFunction) { CANNetworkManager::CANNetwork.add_global_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::LanguageCommand), process_rx_message, this); + + if (respondToRequests && (!myControlFunction->get_pgn_request_protocol().expired())) + { + myControlFunction->get_pgn_request_protocol().lock()->register_pgn_request_callback(static_cast(CANLibParameterGroupNumber::LanguageCommand), on_language_request, this); + } initialized = true; } else @@ -87,16 +98,78 @@ namespace isobus return retVal; } + bool LanguageCommandInterface::send_language_command() const + { + std::array buffer{ + static_cast(languageCode[0]), + static_cast(languageCode[1]), + static_cast((static_cast(timeFormat) << 4) | + (static_cast(decimalSymbol) << 6)), + static_cast(dateFormat), + static_cast(static_cast(massUnitSystem) | + (static_cast(volumeUnitSystem) << 2) | + (static_cast(areaUnitSystem) << 4) | + (static_cast(distanceUnitSystem) << 6)), + static_cast(static_cast(genericUnitSystem) | + (static_cast(forceUnitSystem) << 2) | + (static_cast(pressureUnitSystem) << 4) | + (static_cast(temperatureUnitSystem) << 6)), + static_cast(countryCode[0]), + static_cast(countryCode[1]) + }; + return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::LanguageCommand), + buffer.data(), + buffer.size(), + myControlFunction, + nullptr); + } + std::string LanguageCommandInterface::get_country_code() const { return countryCode; } + void LanguageCommandInterface::set_country_code(std::string country) + { + if (country.length() > 2) + { + CANStackLogger::warn("[VT/TC]: Language command country code should not be more than 2 characters! It will be truncated."); + } + else if (country.length() < 2) + { + CANStackLogger::warn("[VT/TC]: Language command country code should not be less than 2 characters! It will be padded."); + } + + while (country.length() < 2) + { + country.push_back(' '); + } + countryCode = country; + } + std::string LanguageCommandInterface::get_language_code() const { return languageCode; } + void LanguageCommandInterface::set_language_code(std::string language) + { + if (language.length() > 2) + { + CANStackLogger::warn("[VT/TC]: Language command language code should not be more than 2 characters! It will be truncated."); + } + else if (language.length() < 2) + { + CANStackLogger::warn("[VT/TC]: Language command language code should not be less than 2 characters! It will be padded."); + } + + while (language.length() < 2) + { + language.push_back(' '); + } + languageCode = language; + } + std::uint32_t LanguageCommandInterface::get_language_command_timestamp() const { return languageCommandTimestamp_ms; @@ -107,56 +180,111 @@ namespace isobus return decimalSymbol; } + void LanguageCommandInterface::set_commanded_decimal_symbol(DecimalSymbols decimals) + { + decimalSymbol = decimals; + } + LanguageCommandInterface::TimeFormats LanguageCommandInterface::get_commanded_time_format() const { return timeFormat; } + void LanguageCommandInterface::set_commanded_time_format(TimeFormats format) + { + timeFormat = format; + } + LanguageCommandInterface::DateFormats LanguageCommandInterface::get_commanded_date_format() const { return dateFormat; } + void LanguageCommandInterface::set_commanded_date_format(DateFormats format) + { + dateFormat = format; + } + LanguageCommandInterface::DistanceUnits LanguageCommandInterface::get_commanded_distance_units() const { return distanceUnitSystem; } + void LanguageCommandInterface::set_commanded_distance_units(DistanceUnits units) + { + distanceUnitSystem = units; + } + LanguageCommandInterface::AreaUnits LanguageCommandInterface::get_commanded_area_units() const { return areaUnitSystem; } + void LanguageCommandInterface::set_commanded_area_units(AreaUnits units) + { + areaUnitSystem = units; + } + LanguageCommandInterface::VolumeUnits LanguageCommandInterface::get_commanded_volume_units() const { return volumeUnitSystem; } + void LanguageCommandInterface::set_commanded_volume_units(VolumeUnits units) + { + volumeUnitSystem = units; + } + LanguageCommandInterface::MassUnits LanguageCommandInterface::get_commanded_mass_units() const { return massUnitSystem; } + void LanguageCommandInterface::set_commanded_mass_units(MassUnits units) + { + massUnitSystem = units; + } + LanguageCommandInterface::TemperatureUnits LanguageCommandInterface::get_commanded_temperature_units() const { return temperatureUnitSystem; } + void LanguageCommandInterface::set_commanded_temperature_units(TemperatureUnits units) + { + temperatureUnitSystem = units; + } + LanguageCommandInterface::PressureUnits LanguageCommandInterface::get_commanded_pressure_units() const { return pressureUnitSystem; } + void LanguageCommandInterface::set_commanded_pressure_units(PressureUnits units) + { + pressureUnitSystem = units; + } + LanguageCommandInterface::ForceUnits LanguageCommandInterface::get_commanded_force_units() const { return forceUnitSystem; } + void LanguageCommandInterface::set_commanded_force_units(ForceUnits units) + { + forceUnitSystem = units; + } + LanguageCommandInterface::UnitSystem LanguageCommandInterface::get_commanded_generic_units() const { return genericUnitSystem; } + void LanguageCommandInterface::set_commanded_generic_units(UnitSystem units) + { + genericUnitSystem = units; + } + const std::array LanguageCommandInterface::get_localization_raw_data() const { std::array retVal = { 0 }; @@ -229,4 +357,22 @@ namespace isobus } } + bool LanguageCommandInterface::on_language_request(std::uint32_t parameterGroupNumber, + std::shared_ptr, + bool &acknowledge, + AcknowledgementType &acknowledgeType, + void *parentPointer) + { + bool retVal = false; + + if ((nullptr != parentPointer) && (static_cast(CANLibParameterGroupNumber::LanguageCommand) == parameterGroupNumber)) + { + auto targetInterface = static_cast(parentPointer); + acknowledge = false; + acknowledgeType = AcknowledgementType::Positive; + retVal = true; + targetInterface->send_language_command(); + } + return retVal; + } } diff --git a/src/isobus_language_command_interface.hpp b/src/isobus_language_command_interface.hpp index 4911b4c..0e8cae2 100644 --- a/src/isobus_language_command_interface.hpp +++ b/src/isobus_language_command_interface.hpp @@ -10,6 +10,7 @@ #ifndef ISOBUS_LANGUAGE_COMMAND_INTERFACE_HPP #define ISOBUS_LANGUAGE_COMMAND_INTERFACE_HPP +#include "can_callbacks.hpp" #include "can_message.hpp" #include @@ -138,8 +139,9 @@ namespace isobus /// @brief Constructor for a LanguageCommandInterface /// @details This constructor will make a version of the class that will accept the message from any source - /// @param sourceControlFunction The internal control function that the interface should communicate from - explicit LanguageCommandInterface(std::shared_ptr sourceControlFunction); + /// @param[in] sourceControlFunction The internal control function that the interface should communicate from + /// @param[in] shouldRespondToRequests Set this to true if you want this interface to respond to requests for the language command PGN (used in VT/TC servers) + LanguageCommandInterface(std::shared_ptr sourceControlFunction, bool shouldRespondToRequests = false); /// @brief Constructor for a LanguageCommandInterface /// @details This constructor will make a version of the class that will filter the message to be @@ -173,16 +175,32 @@ namespace isobus /// @return `true` if the message was sent, otherwise `false` bool send_request_language_command() const; + /// @brief Sends a language command based on the current content of this class as a broadcast. + /// @note This is only meant to be used by a VT server or TC/DL server + /// @return `true` if the message was sent, otherwise `false` + bool send_language_command() const; + /// @brief Returns the commanded country code parsed from the last language command specifying the operator's desired language dialect. /// @note ISO 11783 networks shall use the alpha-2 country codes in accordance with ISO 3166-1. /// @return The commanded country code, or an empty string if none specified. std::string get_country_code() const; + /// @brief Sets the country code specifying the operator's desired language dialect. + /// @attention This is meant for servers only + /// @note ISO 11783 networks shall use the alpha-2 country codes in accordance with ISO 3166-1. + /// @param[in] country The country code to set + void set_country_code(std::string country); + /// @brief Returns the commanded language code parsed from the last language command /// @note If you do not support the returned language, your default shall be used /// @return The commanded language code (usually 2 characters length) std::string get_language_code() const; + /// @brief Sets the language + /// @attention This is meant for servers only! + /// @param[in] language The language code to set + void set_language_code(std::string language); + /// @brief Returns a timestamp (in ms) corresponding to when the interface last received a language command /// @return timestamp in milliseconds corresponding to when the interface last received a language command std::uint32_t get_language_command_timestamp() const; @@ -191,46 +209,101 @@ namespace isobus /// @return The decimal symbol that was last commanded DecimalSymbols get_commanded_decimal_symbol() const; + /// @brief Sets the decimal symbol to be used. + /// @attention This is meant for servers only! + /// @param[in] decimals The decimal symbol that was last commanded + void set_commanded_decimal_symbol(DecimalSymbols decimals); + /// @brief Returns the commanded time format parsed from the last language command /// @return The time format that was last commanded TimeFormats get_commanded_time_format() const; + /// @brief Sets the commanded time format + /// @attention This is meant for servers only! + /// @param[in] format The time format to set + void set_commanded_time_format(TimeFormats format); + /// @brief Returns the commanded date format parsed from the last language command /// @return The date format that was last commanded DateFormats get_commanded_date_format() const; + /// @brief Sets the commanded date format + /// @attention This is meant for servers only! + /// @param[in] format The date format to set + void set_commanded_date_format(DateFormats format); + /// @brief Returns the commanded distance units parsed from the last language command /// @return The distance units that were last commanded DistanceUnits get_commanded_distance_units() const; + /// @brief Sets the commanded distance units + /// @attention This is meant for servers only! + /// @param[in] units The commanded distance units to set + void set_commanded_distance_units(DistanceUnits units); + /// @brief Returns the commanded area units parsed from the last received language command /// @return The area units that were last commanded AreaUnits get_commanded_area_units() const; + /// @brief Sets the commanded area units + /// @attention This is meant for servers only! + /// @param[in] units The area units to set + void set_commanded_area_units(AreaUnits units); + /// @brief Returns the commanded volume units parsed from the last received language command /// @return The volume units that were last commanded VolumeUnits get_commanded_volume_units() const; + /// @brief Sets the commanded volume units + /// @attention This is meant for servers only! + /// @param[in] units The commanded volume units + void set_commanded_volume_units(VolumeUnits units); + /// @brief Returns the commanded mass units parsed from the last received language command /// @return The mass units that were last commanded MassUnits get_commanded_mass_units() const; + /// @brief Sets the commanded mass units + /// @attention This is meant for servers only! + /// @param[in] units The commanded mass units + void set_commanded_mass_units(MassUnits units); + /// @brief Returns the commanded temperature units parsed from the last received language command /// @return The temperature units that were last commanded TemperatureUnits get_commanded_temperature_units() const; + /// @brief Sets the commanded temperature units + /// @attention This is meant for servers only! + /// @param[in] units The commanded temperature unit system + void set_commanded_temperature_units(TemperatureUnits units); + /// @brief Returns the commanded pressure units parsed from the last received language command /// @return The pressure units that were last commanded PressureUnits get_commanded_pressure_units() const; + /// @brief Sets the commanded pressure units + /// @attention This is meant for servers only! + /// @param[in] units The commanded pressure unit system to command + void set_commanded_pressure_units(PressureUnits units); + /// @brief Returns the commanded force units parsed from the last received language command /// @return The force units that were last commanded ForceUnits get_commanded_force_units() const; + /// @brief Sets the commanded force units + /// @attention This is meant for servers only! + /// @param[in] units The commanded force unit system to command + void set_commanded_force_units(ForceUnits units); + /// @brief Returns the commanded "unit system" generic value that was parsed from the last received language command /// @return The commanded unit system UnitSystem get_commanded_generic_units() const; + /// @brief Sets the commanded generic unit system + /// @attention This is meant for servers only! + /// @param[in] units The commanded generic unit system to command + void set_commanded_generic_units(UnitSystem units); + /// @brief Returns The raw bytes that comprise the current localization data as defined in ISO11783-7 /// @returns The raw bytes that comprise the current localization data const std::array get_localization_raw_data() const; @@ -241,6 +314,19 @@ namespace isobus static void process_rx_message(const CANMessage &message, void *parentPointer); private: + /// @brief This is a callback to handle clients requesting the content of our language data for things like VT/TC servers + /// @param[in] parameterGroupNumber The PGN to handle in the callback + /// @param[in] requestingControlFunction The control function that is requesting the PGN + /// @param[out] acknowledge Tells the stack if we want to send an ACK or NACK + /// @param[out] acknowledgeType Tells the stack exactly how we want to do an ACK + /// @param[in] parentPointer A generic context pointer to locate the specific instance of this class we want + /// @returns `true` if the message was handled, otherwise `false` + static bool on_language_request(std::uint32_t parameterGroupNumber, + std::shared_ptr requestingControlFunction, + bool &acknowledge, + AcknowledgementType &acknowledgeType, + void *parentPointer); + std::shared_ptr myControlFunction; ///< The control function to send messages as std::shared_ptr myPartner; ///< The partner to talk to, or nullptr to listen to all CFs std::string countryCode; ///< The last received alpha-2 country code as specified by ISO 3166-1, such as "NL, FR, GB, US, DE". @@ -258,6 +344,7 @@ namespace isobus ForceUnits forceUnitSystem = ForceUnits::Metric; ///< The force units that were commanded by the last language command message UnitSystem genericUnitSystem = UnitSystem::Metric; ///< The "unit system" that was commanded by the last language command message bool initialized = false; ///< Tracks if initialize has been called yet for this interface + bool respondToRequests = false; ///< Stores if the class should respond to PGN requests for the language command }; } // namespace isobus diff --git a/src/isobus_maintain_power_interface.hpp b/src/isobus_maintain_power_interface.hpp index 7cec012..224dba5 100644 --- a/src/isobus_maintain_power_interface.hpp +++ b/src/isobus_maintain_power_interface.hpp @@ -94,6 +94,7 @@ namespace isobus }; /// @brief Constructor for a MaintainPowerData object, which stores information sent/received in a maintain power message. + /// @param[in] sendingControlFunction The control function to use if sending the message explicit MaintainPowerData(std::shared_ptr sendingControlFunction); /// @brief Sets the reported implement in-work state @@ -218,6 +219,7 @@ namespace isobus /// @brief Returns the content of a received maintain power message /// based on the index of the sender. Use this to read the received messages' content. /// @param[in] index An index of senders of the maintain power message + /// @returns A pointer to the maintain power message data, or nullptr if the index is out of range std::shared_ptr get_received_maintain_power(std::size_t index); /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated maintain power messages are received. diff --git a/src/isobus_preferred_addresses.hpp b/src/isobus_preferred_addresses.hpp new file mode 100644 index 0000000..4f8fb59 --- /dev/null +++ b/src/isobus_preferred_addresses.hpp @@ -0,0 +1,225 @@ +//================================================================================================ +/// @file isobus_preferred_addresses.hpp +/// +/// @brief This is a reference for control function's preferred addresses as defined by +/// ISO 11783-11 and/or SAE. Preferred addresses are industry group specific. +/// You should use these when your are creating a control function that is a well known +/// function type, but if your control function doesn't arbitrate for that address, the +/// stack will claim for you in the dynamic address range. +/// +/// @author Adrian Del Grosso +/// +/// @copyright 2024 The Open-Agriculture Developers +//================================================================================================ +#ifndef ISOBUS_PREFERRED_ADDRESSES_HPP +#define ISOBUS_PREFERRED_ADDRESSES_HPP + +#include + +namespace isobus +{ + /// @brief This namespace contains all defined preferred addresses for control functions, which + /// should be used when creating a control function that is a well known function type. + namespace preferred_addresses + { + /// @brief Industry Group 1 applies to on-highway equipment. + namespace IndustryGroup1 + { + /// This enumerates all preferred addresses for industry group 1. + enum PreferredAddress : std::uint8_t + { + // 128-158 are reserved for future assignment by SAE but available for use by self configurable ECUs + AutomatedDrivingController2 = 156, + ElectricPropulsionControlUnit3 = 157, + AutomatedDrivingController1 = 158, + RoadwayInformationSystem = 159, + AdvancedEmergencyBrakingSystem = 160, + FifthWheelSmartSystems = 161, + SlopeSensor = 162, + CatalystFluidSensor = 163, + OnBoardDiagnosticUnit2 = 164, + RearSteeringAxleController2 = 165, + RearSteeringAxleController3 = 166, + InstrumentCluster2 = 167, + Trailer5Bridge = 168, + Trailer5LightingElectrical = 169, + Trailer5BrakesABS_EBS = 170, + Trailer5Reefer = 171, + Trailer5Cargo = 172, + Trailer5ChassisSuspension = 173, + OtherTrailer5Devices = 174, + OtherTrailer5Devices2 = 175, + Trailer4Bridge = 176, + Trailer4LightingElectrical = 177, + Trailer4BrakesABS_EBS = 178, + Trailer4Reefer = 179, + Trailer4Cargo = 180, + Trailer4ChassisSuspension = 181, + OtherTrailer4Devices = 182, + OtherTrailer4Devices2 = 183, + Trailer3Bridge = 184, + Trailer3LightingElectrical = 185, + Trailer3BrakesABS_EBS = 186, + Trailer3Reefer = 187, + Trailer3Cargo = 188, + Trailer3ChassisSuspension = 189, + OtherTrailer3Devices = 190, + OtherTrailer3Devices2 = 191, + Trailer2Bridge = 192, + Trailer2LightingElectrical = 193, + Trailer2BrakesABS_EBS = 194, + Trailer2Reefer = 195, + Trailer2Cargo = 196, + Trailer2ChassisSuspension = 197, + OtherTrailer2Devices = 198, + OtherTrailer2Devices2 = 199, + Trailer1Bridge = 200, + Trailer1LightingElectrical = 201, + Trailer1BrakesABS_EBS = 202, + Trailer1Reefer = 203, + Trailer1Cargo = 204, + Trailer1ChassisSuspension = 205, + OtherTrailer1Devices = 206, + OtherTrailer1Devices2 = 207, + SteeringBodyUnit = 228, + BodyController2 = 229, + BodyToVehicleInterfaceControl = 230, + ArticulationTurntableControl = 231, + ForwardRoadImageProcessor = 232, + DoorController3 = 233, + DoorController4 = 234, + TractorTrailerBridge2 = 235, + DoorController1 = 236, + DoorController2 = 237, + Tachograph = 238, + ElectricPropulsionControlUnit1 = 239, + ElectricPropulsionControlUnit2 = 240, + WWH_OBDTester = 241, + ElectricPropulsionControlUnit4 = 242, + BatteryPackMonitor1 = 243, + BatteryPackMonitor2_APU4 = 244, + BatteryPackMonitor3_APU3 = 245, + BatteryPackMonitor4_APU2 = 246, + AuxiliaryPowerUnit_APU1 = 247 + }; + } // namespace IndustryGroup1 + + /// @brief Industry Group 2 applies to agricultural and forestry equipment. + namespace IndustryGroup2 + { + /// This enumerates all preferred addresses for industry group 2. + enum PreferredAddress : std::uint8_t + { + // 128-235 are reserved by ISO for the self-configurable address capability + DataLogger = 236, + TIMServer = 237, + SequenceController = 238, + PositionControl = 239, + TractorECU = 240, + TailingsMonitoring = 241, + HeaderControl = 242, + ProductLossMonitoring = 243, + ProductMoistureSensing = 244, + NonVirtualTerminalDisplay_ImplementBus = 245, + OperatorControls_MachineSpecific = 246, + TaskController_MappingComputer = 247 + }; + } // namespace IndustryGroup1 + + /// @brief Industry Group 3 applies to construction equipment. + namespace IndustryGroup3 + { + /// This enumerates all preferred addresses for industry group 3. + enum PreferredAddress : std::uint8_t + { + /// 128 thru 207 are reserved for future assignment by SAE + /// 208 thru 223 are reserved for future assignment + RotationSensor = 224, + LiftArmController = 225, + SlopeSensor = 226, + MainController_SkidSteerLoader = 227, + LoaderControl = 228, + LaserTracer = 229, + LandLevelingSystemDisplay = 230, + SingleLandLevelingSystemSupervisor = 231, + LandLevelingElectricMast = 232, + SingleLandLevelingSystemOperatorInterface = 233, + LaserReceiver = 234, + SupplementalSensorProcessingUnit1 = 235, + SupplementalSensorProcessingUnit2 = 236, + SupplementalSensorProcessingUnit3 = 237, + SupplementalSensorProcessingUnit4 = 238, + SupplementalSensorProcessingUnit5 = 239, + SupplementalSensorProcessingUnit6 = 240, + EngineMonitor1 = 241, + EngineMonitor2 = 242, + EngineMonitor3 = 243, + EngineMonitor4 = 244, + EngineMonitor5 = 245, + EngineMonitor6 = 246, + EngineMonitor7 = 247 + }; + } // namespace IndustryGroup3 + + /// @brief Industry Group 4 applies to marine equipment. + namespace IndustryGroup4 + { + /// This enumerates all preferred addresses for industry group 4. + enum PreferredAddress : std::uint8_t + { + /// 128 thru 207 are reserved for future assignment by SAE + /// 208 thru 227 are reserved for future assignment + PropulsionSensorHubAndGateway1 = 228, + PropulsionSensorHubAndGateway2 = 229, + PropulsionSensorHubAndGateway3 = 230, + PropulsionSensorHubAndGateway4 = 231, + Transmission3 = 232, + Transmission4 = 233, + Transmission5 = 234, + Transmission6 = 235, + Display1forProtectionSystemforMarineEngines = 236, + ProtectionSystemforMarineEngines = 237, + AlarmSystemControl1forMarineEngines = 238, + Engine3 = 239, + Engine4 = 240, + Engine5 = 241, + MarineDisplay1 = 242, + MarineDisplay2 = 243, + MarineDisplay3 = 244, + MarineDisplay4 = 245, + MarineDisplay5 = 246, + MarineDisplay6 = 247 + }; + } // namespace IndustryGroup4 + + /// @brief Industry Group 5 applies to industrial process control stationary equipment (Gen-sets). + namespace IndustryGroup5 + { + /// This enumerates all preferred addresses for industry group 5. + enum PreferredAddress : std::uint8_t + { + /// 128 thru 207 are reserved for future assignment by SAE + /// 208 thru 229 are reserved for future assignment + GeneratorVoltageRegulator = 230, + Engine3 = 231, + Engine4 = 232, + Engine5 = 233, + GeneratorSetController = 234, + SupplementalSensorProcessingUnit1 = 235, + SupplementalSensorProcessingUnit2 = 236, + SupplementalSensorProcessingUnit3 = 237, + SupplementalSensorProcessingUnit4 = 238, + SupplementalSensorProcessingUnit5 = 239, + SupplementalSensorProcessingUnit6 = 240, + EngineMonitor1 = 241, + EngineMonitor2 = 242, + EngineMonitor3 = 243, + EngineMonitor4 = 244, + EngineMonitor5 = 245, + EngineMonitor6 = 246, + EngineMonitor7 = 247 + }; + } // namespace IndustryGroup5 + } // namespace preferred_addresses +} // namespace isobus +#endif // ISOBUS_PREFERRED_ADDRESSES_HPP diff --git a/src/isobus_shortcut_button_interface.cpp b/src/isobus_shortcut_button_interface.cpp index 511b367..08656a3 100644 --- a/src/isobus_shortcut_button_interface.cpp +++ b/src/isobus_shortcut_button_interface.cpp @@ -231,6 +231,6 @@ namespace isobus buffer.size(), sourceControlFunction, nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } } diff --git a/src/isobus_speed_distance_messages.cpp b/src/isobus_speed_distance_messages.cpp index 2c32bc5..6673883 100644 --- a/src/isobus_speed_distance_messages.cpp +++ b/src/isobus_speed_distance_messages.cpp @@ -813,7 +813,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(machineSelectedSpeedTransmitData.get_sender_control_function()), nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } @@ -840,7 +840,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(wheelBasedSpeedTransmitData.get_sender_control_function()), nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } @@ -864,7 +864,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(groundBasedSpeedTransmitData.get_sender_control_function()), nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } @@ -888,7 +888,7 @@ namespace isobus buffer.size(), std::static_pointer_cast(machineSelectedSpeedCommandTransmitData.get_sender_control_function()), nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } return retVal; } diff --git a/src/isobus_speed_distance_messages.hpp b/src/isobus_speed_distance_messages.hpp index 414dd18..046bfa8 100644 --- a/src/isobus_speed_distance_messages.hpp +++ b/src/isobus_speed_distance_messages.hpp @@ -523,6 +523,7 @@ namespace isobus /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The parsed content of the machine selected speed message std::shared_ptr get_received_machine_selected_speed(std::size_t index); /// @brief Returns the content of the wheel-based speed message @@ -531,6 +532,7 @@ namespace isobus /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The parsed content of the wheel-based speed message std::shared_ptr get_received_wheel_based_speed(std::size_t index); /// @brief Returns the content of the ground-based speed message @@ -539,6 +541,7 @@ namespace isobus /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The parsed content of the ground-based speed message std::shared_ptr get_received_ground_based_speed(std::size_t index); /// @brief Returns the content of the machine selected speed command message @@ -547,6 +550,7 @@ namespace isobus /// @note Only one device on the bus will send this normally, but we provide a generic way to get /// an arbitrary number of these commands. So generally using only index 0 will be acceptable. /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The parsed content of the machine selected speed command message std::shared_ptr get_received_machine_selected_speed_command(std::size_t index); /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated wheel-based speed messages are received. diff --git a/src/isobus_task_controller_client.cpp b/src/isobus_task_controller_client.cpp index 7903c66..44e459a 100644 --- a/src/isobus_task_controller_client.cpp +++ b/src/isobus_task_controller_client.cpp @@ -230,6 +230,17 @@ namespace isobus } } + void TaskControllerClient::restart() + { + if (initialized) + { +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + const std::lock_guard lock(clientMutex); +#endif + set_state(StateMachineState::Disconnected); + } + } + void TaskControllerClient::terminate() { if (initialized) @@ -244,7 +255,7 @@ namespace isobus shouldTerminate = true; #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO - if (nullptr != workerThread) + if ((nullptr != workerThread) && (workerThread->get_id() != std::this_thread::get_id())) { workerThread->join(); delete workerThread; @@ -319,6 +330,87 @@ namespace isobus return (get_is_connected() && (0 != (0x01 & tcStatusBitfield))); } + bool TaskControllerClient::reupload_device_descriptor_object_pool(std::shared_ptr> binaryDDOP) + { + bool retVal = false; +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + const std::lock_guard lock(clientMutex); +#endif + + if (StateMachineState::Connected == get_state()) + { + assert(nullptr != binaryDDOP); // Client will not work without a DDOP. + assert(!binaryDDOP->empty()); // Client will not work without a DDOP. + ddopStructureLabel.clear(); + generatedBinaryDDOP.clear(); + ddopLocalizationLabel.fill(0x00); + userSuppliedVectorDDOP = binaryDDOP; + ddopUploadMode = DDOPUploadType::UserProvidedVector; + userSuppliedBinaryDDOP = nullptr; + userSuppliedBinaryDDOPSize_bytes = 0; + shouldReuploadAfterDDOPDeletion = true; + set_state(StateMachineState::DeactivateObjectPool); + clear_queues(); + retVal = true; + CANStackLogger::info("[TC]: Requested to change the DDOP. Object pool will be deactivated for a little while."); + } + return retVal; + } + + bool TaskControllerClient::reupload_device_descriptor_object_pool(std::uint8_t const *binaryDDOP, std::uint32_t DDOPSize) + { + bool retVal = false; +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + const std::lock_guard lock(clientMutex); +#endif + + if (StateMachineState::Connected == get_state()) + { + assert(nullptr != binaryDDOP); // Client will not work without a DDOP. + assert(0 != DDOPSize); + generatedBinaryDDOP.clear(); + ddopStructureLabel.clear(); + userSuppliedVectorDDOP = nullptr; + ddopLocalizationLabel.fill(0x00); + ddopUploadMode = DDOPUploadType::UserProvidedBinaryPointer; + userSuppliedBinaryDDOP = binaryDDOP; + userSuppliedBinaryDDOPSize_bytes = DDOPSize; + shouldReuploadAfterDDOPDeletion = true; + set_state(StateMachineState::DeactivateObjectPool); + clear_queues(); + retVal = true; + CANStackLogger::info("[TC]: Requested to change the DDOP. Object pool will be deactivated for a little while."); + } + return retVal; + } + + bool TaskControllerClient::reupload_device_descriptor_object_pool(std::shared_ptr DDOP) + { + bool retVal = false; +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + const std::lock_guard lock(clientMutex); +#endif + + if (StateMachineState::Connected == get_state()) + { + assert(nullptr != DDOP); // Client will not work without a DDOP. + generatedBinaryDDOP.clear(); + ddopStructureLabel.clear(); + userSuppliedVectorDDOP = nullptr; + ddopLocalizationLabel.fill(0x00); + ddopUploadMode = DDOPUploadType::ProgramaticallyGenerated; + clientDDOP = DDOP; + userSuppliedBinaryDDOP = nullptr; + userSuppliedBinaryDDOPSize_bytes = 0; + shouldReuploadAfterDDOPDeletion = true; + set_state(StateMachineState::DeactivateObjectPool); + clear_queues(); + retVal = true; + CANStackLogger::info("[TC]: Requested to change the DDOP. Object pool will be deactivated for a little while."); + } + return retVal; + } + void TaskControllerClient::update() { switch (currentState) @@ -326,6 +418,7 @@ namespace isobus case StateMachineState::Disconnected: { enableStatusMessage = false; + shouldReuploadAfterDDOPDeletion = false; if (get_was_ddop_supplied()) { @@ -480,6 +573,13 @@ namespace isobus { process_labels_from_ddop(); CANStackLogger::debug("[TC]: DDOP Generated, size: " + isobus::to_string(static_cast(generatedBinaryDDOP.size()))); + + if ((!previousStructureLabel.empty()) && (ddopStructureLabel == previousStructureLabel)) + { + CANStackLogger::error("[TC]: You didn't properly update your new DDOP's structure label. ISO11783-10 states that an update to an object pool must include an updated structure label."); + } + previousStructureLabel = ddopStructureLabel; + set_state(StateMachineState::RequestStructureLabel); } else @@ -740,9 +840,18 @@ namespace isobus { if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, TWO_SECOND_TIMEOUT_MS)) { - CANStackLogger::error("[TC]: Timeout waiting for deactivate object pool response. Client terminated."); - set_state(StateMachineState::Disconnected); - terminate(); + if (shouldReuploadAfterDDOPDeletion) + { + CANStackLogger::warn("[TC]: Timeout waiting for deactivate object pool response. This is unusual, but we're just going to reconnect anyways."); + shouldReuploadAfterDDOPDeletion = false; + set_state(StateMachineState::ProcessDDOP); + } + else + { + CANStackLogger::error("[TC]: Timeout waiting for deactivate object pool response. Client terminated."); + set_state(StateMachineState::Disconnected); + terminate(); + } } } break; @@ -1093,7 +1202,7 @@ namespace isobus std::uint32_t targetParameterGroupNumber = message.get_uint24_at(5); if (static_cast(CANLibParameterGroupNumber::ProcessData) == targetParameterGroupNumber) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[TC]: The TC Server is NACK-ing our messages. Disconnecting."); + CANStackLogger::error("[TC]: The TC Server is NACK-ing our messages. Disconnecting."); parentTC->set_state(StateMachineState::Disconnected); } } @@ -1356,6 +1465,11 @@ namespace isobus if (0 == messageData[1]) { CANStackLogger::info("[TC]: Object pool deactivated OK."); + + if (parentTC->shouldReuploadAfterDDOPDeletion) + { + parentTC->set_state(StateMachineState::SendDeleteObjectPool); + } } else { @@ -1371,7 +1485,7 @@ namespace isobus case DeviceDescriptorCommands::ObjectPoolDeleteResponse: { - // Message content of this is unreliable, the standard is ambigious on what to even check. + // Message content of this is unreliable, the standard is ambiguous on what to even check. // Plus, if the delete failed, the recourse is the same, always proceed. if (StateMachineState::WaitForDeleteObjectPoolResponse == parentTC->get_state()) { diff --git a/src/isobus_task_controller_client.hpp b/src/isobus_task_controller_client.hpp index 75d046f..2b1beb1 100644 --- a/src/isobus_task_controller_client.hpp +++ b/src/isobus_task_controller_client.hpp @@ -211,6 +211,10 @@ namespace isobus bool reportToTCSupportsPeerControlAssignment, bool reportToTCSupportsImplementSectionControl); + /// @brief Calling this function will reset the task controller client's connection + /// with the TC server, and cause it to reconnect after a short delay. + void restart(); + // Calling this will stop the worker thread if it exists /// @brief Terminates the client and joins the worker thread if applicable void terminate(); @@ -304,6 +308,8 @@ namespace isobus /// a value to the TC server. /// @details If you provide on-change triggers in your DDOP, this is how you can request the TC client /// to update the TC server on the current value of your process data variables. + /// @param[in] elementNumber The element number of the process data variable that changed + /// @param[in] DDI The DDI of the process data variable that changed void on_value_changed_trigger(std::uint16_t elementNumber, std::uint16_t DDI); /// @brief Sends a broadcast request to TCs to identify themseleves. @@ -311,6 +317,34 @@ namespace isobus /// @returns `true` if the message was sent, otherwise `false` bool request_task_controller_identification() const; + /// @brief If the TC client is connected to a TC, calling this function will + /// cause the TC client interface to delete the currently active DDOP, reupload it, + /// then reactivate it using the pool passed into the parameter of this function. + /// This process is faster than restarting the whole interface, and you have to + /// call it if you change certain things in your DDOP at runtime after the DDOP has already been activated. + /// @param[in] binaryDDOP The updated device descriptor object pool to upload to the TC + /// @returns true if the interface accepted the command to reupload the pool, or false if the command cannot be handled right now + bool reupload_device_descriptor_object_pool(std::shared_ptr> binaryDDOP); + + /// @brief If the TC client is connected to a TC, calling this function will + /// cause the TC client interface to delete the currently active DDOP, reupload it, + /// then reactivate it using the pool passed into the parameter of this function. + /// This process is faster than restarting the whole interface, and you have to + /// call it if you change certain things in your DDOP at runtime after the DDOP has already been activated. + /// @param[in] binaryDDOP The updated device descriptor object pool to upload to the TC + /// @param[in] DDOPSize The number of bytes in the binary DDOP that will be uploaded + /// @returns true if the interface accepted the command to reupload the pool, or false if the command cannot be handled right now + bool reupload_device_descriptor_object_pool(std::uint8_t const *binaryDDOP, std::uint32_t DDOPSize); + + /// @brief If the TC client is connected to a TC, calling this function will + /// cause the TC client interface to delete the currently active DDOP, reupload it, + /// then reactivate it using the pool passed into the parameter of this function. + /// This process is faster than restarting the whole interface, and you have to + /// call it if you change certain things in your DDOP at runtime after the DDOP has already been activated. + /// @param[in] DDOP The updated device descriptor object pool to upload to the TC + /// @returns true if the interface accepted the command to reupload the pool, or false if the command cannot be handled right now + bool reupload_device_descriptor_object_pool(std::shared_ptr DDOP); + /// @brief The cyclic update function for this interface. /// @note This function may be called by the TC worker thread if you called /// initialize with a parameter of `true`, otherwise you must call it @@ -406,6 +440,12 @@ namespace isobus static void process_rx_message(const CANMessage &message, void *parentPointer); /// @brief The callback passed to the network manager's send function to know when a Tx is completed + /// @param[in] parameterGroupNumber The parameter group number of the message that was sent + /// @param[in] dataLength The number of bytes sent + /// @param[in] sourceControlFunction The control function that sent the message + /// @param[in] destinationControlFunction The control function that received the message + /// @param[in] successful Whether the message was sent successfully + /// @param[in] parentPointer A context variable that is passed back through the callback static void process_tx_callback(std::uint32_t parameterGroupNumber, std::uint32_t dataLength, std::shared_ptr sourceControlFunction, @@ -422,6 +462,7 @@ namespace isobus /// @brief Sends a process data message with 1 mux byte and all 0xFFs as payload /// @details This just reduces code duplication by consolidating common message formats + /// @param[in] multiplexor The multiplexor to use for the message /// @returns `true` if the message was sent, otherwise `false` bool send_generic_process_data(std::uint8_t multiplexor) const; @@ -475,6 +516,9 @@ namespace isobus bool send_status() const; /// @brief Sends the value command message for a specific DDI/Element number combo + /// @param[in] elementNumber The element number for the command + /// @param[in] ddi The DDI for the command + /// @param[in] value The value to send /// @returns `true` if the message was sent, otherwise `false` bool send_value_command(std::uint16_t elementNumber, std::uint16_t ddi, std::uint32_t value) const; @@ -526,6 +570,7 @@ namespace isobus { /// @brief Allows easy comparison of callback data /// @param obj the object to compare against + /// @returns true if the ddi and element numbers of the provided objects match, otherwise false bool operator==(const ProcessDataCallbackInfo &obj) const; std::uint32_t processDataValue; ///< The value of the value set command std::uint32_t lastValue; ///< Used for measurement commands to store timestamp or previous values @@ -540,8 +585,9 @@ namespace isobus { /// @brief Allows easy comparison of callback data /// @param obj the object to compare against + /// @returns true if the callback and parent pointer match, otherwise false bool operator==(const RequestValueCommandCallbackInfo &obj) const; - RequestValueCommandCallback callback = nullptr; ///< The callback itself + RequestValueCommandCallback callback; ///< The callback itself void *parent; ///< The parent pointer, generic context value }; @@ -550,6 +596,7 @@ namespace isobus { /// @brief Allows easy comparison of callback data /// @param obj the object to compare against + /// @returns true if the callback and parent pointer match, otherwise false bool operator==(const ValueCommandCallbackInfo &obj) const; ValueCommandCallback callback; ///< The callback itself void *parent; ///< The parent pointer, generic context value @@ -583,6 +630,7 @@ namespace isobus std::thread *workerThread = nullptr; ///< The worker thread that updates this interface #endif std::string ddopStructureLabel; ///< Stores a pre-parsed structure label, helps to avoid processing the whole DDOP during a CAN message callback + std::string previousStructureLabel; ///< Stores the last structure label we used, helps to warn the user if they aren't updating the label properly std::array ddopLocalizationLabel = { 0 }; ///< Stores a pre-parsed localization label, helps to avoid processing the whole DDOP during a CAN message callback DDOPUploadType ddopUploadMode = DDOPUploadType::ProgramaticallyGenerated; ///< Determines if DDOPs get generated or raw uploaded StateMachineState currentState = StateMachineState::Disconnected; ///< Tracks the internal state machine's current state @@ -612,6 +660,7 @@ namespace isobus bool supportsTCGEOWithPositionBasedControl = false; ///< Determines if the client reports TC-GEO with position control capability to the TC bool supportsPeerControlAssignment = false; ///< Determines if the client reports peer control assignment capability to the TC bool supportsImplementSectionControl = false; ///< Determines if the client reports implement section control capability to the TC + bool shouldReuploadAfterDDOPDeletion = false; ///< Used to determine how the state machine should progress when updating a DDOP }; } // namespace isobus diff --git a/src/isobus_task_controller_client_objects.cpp b/src/isobus_task_controller_client_objects.cpp index b647f58..9f0d200 100644 --- a/src/isobus_task_controller_client_objects.cpp +++ b/src/isobus_task_controller_client_objects.cpp @@ -8,6 +8,7 @@ //================================================================================================ #include "isobus_task_controller_client_objects.hpp" +#include "can_constants.hpp" #include "platform_endianness.hpp" #include diff --git a/src/isobus_task_controller_client_objects.hpp b/src/isobus_task_controller_client_objects.hpp index f80c1e0..8133beb 100644 --- a/src/isobus_task_controller_client_objects.hpp +++ b/src/isobus_task_controller_client_objects.hpp @@ -72,9 +72,6 @@ namespace isobus /// @brief The max allowable "valid" object ID static constexpr std::uint16_t MAX_OBJECT_ID = 65534; - /// @brief Special ID used to indicate no object - static constexpr std::uint16_t NULL_OBJECT_ID = 65535; - /// @brief Defines the max length of a designator (in bytes) static constexpr std::size_t MAX_DESIGNATOR_LENGTH = 128; @@ -280,6 +277,7 @@ namespace isobus std::size_t get_number_child_objects() const; /// @brief Returns a child object ID by index + /// @param[in] index The index of the child object ID to return /// @returns Child object ID by index, or NULL_OBJECT_ID if the index is out of range std::uint16_t get_child_object_id(std::size_t index); diff --git a/src/isobus_virtual_terminal_client.cpp b/src/isobus_virtual_terminal_client.cpp index 9ccf162..569782f 100644 --- a/src/isobus_virtual_terminal_client.cpp +++ b/src/isobus_virtual_terminal_client.cpp @@ -145,64 +145,64 @@ namespace isobus return retVal; } - std::shared_ptr VirtualTerminalClient::add_vt_soft_key_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_soft_key_event_dispatcher() { - return softKeyEventDispatcher.add_listener(callback); + return softKeyEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_button_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_button_event_dispatcher() { - return buttonEventDispatcher.add_listener(callback); + return buttonEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_pointing_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_pointing_event_dispatcher() { - return pointingEventDispatcher.add_listener(callback); + return pointingEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_select_input_object_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_select_input_object_event_dispatcher() { - return selectInputObjectEventDispatcher.add_listener(callback); + return selectInputObjectEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_esc_message_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_esc_message_event_dispatcher() { - return escMessageEventDispatcher.add_listener(callback); + return escMessageEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_change_numeric_value_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_change_numeric_value_event_dispatcher() { - return changeNumericValueEventDispatcher.add_listener(callback); + return changeNumericValueEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_change_active_mask_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_change_active_mask_event_dispatcher() { - return changeActiveMaskEventDispatcher.add_listener(callback); + return changeActiveMaskEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_change_soft_key_mask_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_change_soft_key_mask_event_dispatcher() { - return changeSoftKeyMaskEventDispatcher.add_listener(callback); + return changeSoftKeyMaskEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_change_string_value_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_change_string_value_event_dispatcher() { - return changeStringValueEventDispatcher.add_listener(callback); + return changeStringValueEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_user_layout_hide_show_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_user_layout_hide_show_event_dispatcher() { - return userLayoutHideShowEventDispatcher.add_listener(callback); + return userLayoutHideShowEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_vt_control_audio_signal_termination_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_vt_control_audio_signal_termination_event_dispatcher() { - return audioSignalTerminationEventDispatcher.add_listener(callback); + return audioSignalTerminationEventDispatcher; } - std::shared_ptr VirtualTerminalClient::add_auxiliary_function_event_listener(std::function callback) + EventDispatcher &VirtualTerminalClient::get_auxiliary_function_event_dispatcher() { - return auxiliaryFunctionEventDispatcher.add_listener(callback); + return auxiliaryFunctionEventDispatcher; } void VirtualTerminalClient::set_auxiliary_input_model_identification_code(std::uint16_t modelIdentificationCode) @@ -260,98 +260,72 @@ namespace isobus return (functionObjectID == other.functionObjectID) && (inputObjectID == other.inputObjectID) && (functionType == other.functionType); } - bool VirtualTerminalClient::send_hide_show_object(std::uint16_t objectID, HideShowObjectCommand command) const + bool VirtualTerminalClient::send_hide_show_object(std::uint16_t objectID, HideShowObjectCommand command) { - const std::array buffer = { static_cast(Function::HideShowObjectCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(command), - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::HideShowObjectCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(command), + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_enable_disable_object(std::uint16_t objectID, EnableDisableObjectCommand command) const + bool VirtualTerminalClient::send_enable_disable_object(std::uint16_t objectID, EnableDisableObjectCommand command) { - const std::array buffer = { static_cast(Function::EnableDisableObjectCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(command), - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::EnableDisableObjectCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(command), + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_select_input_object(std::uint16_t objectID, SelectInputObjectOptions option) const + bool VirtualTerminalClient::send_select_input_object(std::uint16_t objectID, SelectInputObjectOptions option) { - const std::array buffer = { static_cast(Function::SelectInputObjectCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(option), - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::SelectInputObjectCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(option), + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_ESC() const + bool VirtualTerminalClient::send_ESC() { - const std::array buffer = { static_cast(Function::ESCCommand), - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ESCCommand), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_control_audio_signal(std::uint8_t activations, std::uint16_t frequency_hz, std::uint16_t duration_ms, std::uint16_t offTimeDuration_ms) const + bool VirtualTerminalClient::send_control_audio_signal(std::uint8_t activations, std::uint16_t frequency_hz, std::uint16_t duration_ms, std::uint16_t offTimeDuration_ms) { - const std::array buffer = { static_cast(Function::ControlAudioSignalCommand), - activations, - static_cast(frequency_hz & 0xFF), - static_cast(frequency_hz >> 8), - static_cast(duration_ms & 0xFF), - static_cast(duration_ms >> 8), - static_cast(offTimeDuration_ms & 0xFF), - static_cast(offTimeDuration_ms >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ControlAudioSignalCommand), + activations, + static_cast(frequency_hz & 0xFF), + static_cast(frequency_hz >> 8), + static_cast(duration_ms & 0xFF), + static_cast(duration_ms >> 8), + static_cast(offTimeDuration_ms & 0xFF), + static_cast(offTimeDuration_ms >> 8) }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_set_audio_volume(std::uint8_t volume_percent) const + bool VirtualTerminalClient::send_set_audio_volume(std::uint8_t volume_percent) { constexpr std::uint8_t MAX_VOLUME_PERCENT = 100; @@ -361,43 +335,33 @@ namespace isobus CANStackLogger::warn("[VT]: Cannot try to set audio volume greater than 100 percent. Value will be capped at 100."); } - const std::array buffer = { static_cast(Function::SetAudioVolumeCommand), - volume_percent, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::SetAudioVolumeCommand), + volume_percent, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_change_child_location(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint8_t relativeXPositionChange, std::uint8_t relativeYPositionChange) const + bool VirtualTerminalClient::send_change_child_location(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint8_t relativeXPositionChange, std::uint8_t relativeYPositionChange) { - const std::array buffer = { static_cast(Function::ChangeChildLocationCommand), - static_cast(parentObjectID & 0xFF), - static_cast(parentObjectID >> 8), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - relativeXPositionChange, - relativeYPositionChange, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeChildLocationCommand), + static_cast(parentObjectID & 0xFF), + static_cast(parentObjectID >> 8), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + relativeXPositionChange, + relativeYPositionChange, + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_child_position(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint16_t xPosition, std::uint16_t yPosition) const + bool VirtualTerminalClient::send_change_child_position(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint16_t xPosition, std::uint16_t yPosition) { - const std::array buffer = { + const std::vector buffer = { static_cast(Function::ChangeChildPositionCommand), static_cast(parentObjectID & 0xFF), static_cast(parentObjectID >> 8), @@ -408,53 +372,38 @@ namespace isobus static_cast(yPosition & 0xFF), static_cast(yPosition >> 8), }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_size_command(std::uint16_t objectID, std::uint16_t newWidth, std::uint16_t newHeight) const + bool VirtualTerminalClient::send_change_size_command(std::uint16_t objectID, std::uint16_t newWidth, std::uint16_t newHeight) { - const std::array buffer = { static_cast(Function::ChangeSizeCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(newWidth & 0xFF), - static_cast(newWidth >> 8), - static_cast(newHeight & 0xFF), - static_cast(newHeight >> 8), - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeSizeCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(newWidth & 0xFF), + static_cast(newWidth >> 8), + static_cast(newHeight & 0xFF), + static_cast(newHeight >> 8), + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_background_colour(std::uint16_t objectID, std::uint8_t colour) const + bool VirtualTerminalClient::send_change_background_colour(std::uint16_t objectID, std::uint8_t colour) { - const std::array buffer = { static_cast(Function::ChangeBackgroundColourCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - colour, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeBackgroundColourCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + colour, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_numeric_value(std::uint16_t objectID, std::uint32_t value) const + bool VirtualTerminalClient::send_change_numeric_value(std::uint16_t objectID, std::uint32_t value) { - const std::array buffer = { + const std::vector buffer = { static_cast(Function::ChangeNumericValueCommand), static_cast(objectID & 0xFF), static_cast(objectID >> 8), @@ -464,15 +413,10 @@ namespace isobus static_cast((value >> 16) & 0xFF), static_cast((value >> 24) & 0xFF), }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_string_value(std::uint16_t objectID, uint16_t stringLength, const char *value) const + bool VirtualTerminalClient::send_change_string_value(std::uint16_t objectID, uint16_t stringLength, const char *value) { bool retVal = false; @@ -494,148 +438,108 @@ namespace isobus { buffer.push_back(0xFF); // Pad to minimum length } - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + retVal = queue_command(buffer); } return retVal; } - bool VirtualTerminalClient::send_change_string_value(std::uint16_t objectID, const std::string &value) const + bool VirtualTerminalClient::send_change_string_value(std::uint16_t objectID, const std::string &value) { return send_change_string_value(objectID, value.size(), value.c_str()); } - bool VirtualTerminalClient::send_change_endpoint(std::uint16_t objectID, std::uint16_t width_px, std::uint16_t height_px, LineDirection direction) const + bool VirtualTerminalClient::send_change_endpoint(std::uint16_t objectID, std::uint16_t width_px, std::uint16_t height_px, LineDirection direction) { - const std::array buffer = { static_cast(Function::ChangeEndPointCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(width_px & 0xFF), - static_cast(width_px >> 8), - static_cast(height_px & 0xFF), - static_cast(height_px >> 8), - static_cast(direction) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeEndPointCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(width_px & 0xFF), + static_cast(width_px >> 8), + static_cast(height_px & 0xFF), + static_cast(height_px >> 8), + static_cast(direction) }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_font_attributes(std::uint16_t objectID, std::uint8_t colour, FontSize size, std::uint8_t type, std::uint8_t styleBitfield) const + bool VirtualTerminalClient::send_change_font_attributes(std::uint16_t objectID, std::uint8_t colour, FontSize size, std::uint8_t type, std::uint8_t styleBitfield) { - const std::array buffer = { static_cast(Function::ChangeFontAttributesCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - colour, - static_cast(size), - type, - styleBitfield, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeFontAttributesCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + colour, + static_cast(size), + type, + styleBitfield, + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_line_attributes(std::uint16_t objectID, std::uint8_t colour, std::uint8_t width, std::uint16_t lineArtBitmask) const + bool VirtualTerminalClient::send_change_line_attributes(std::uint16_t objectID, std::uint8_t colour, std::uint8_t width, std::uint16_t lineArtBitmask) { - const std::array buffer = { static_cast(Function::ChangeLineAttributesCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - colour, - static_cast(width), - static_cast(lineArtBitmask & 0xFF), - static_cast(lineArtBitmask >> 8), - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeLineAttributesCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + colour, + static_cast(width), + static_cast(lineArtBitmask & 0xFF), + static_cast(lineArtBitmask >> 8), + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_fill_attributes(std::uint16_t objectID, FillType fillType, std::uint8_t colour, std::uint16_t fillPatternObjectID) const + bool VirtualTerminalClient::send_change_fill_attributes(std::uint16_t objectID, FillType fillType, std::uint8_t colour, std::uint16_t fillPatternObjectID) { - const std::array buffer = { static_cast(Function::ChangeFillAttributesCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(fillType), - colour, - static_cast(fillPatternObjectID & 0xFF), - static_cast(fillPatternObjectID >> 8), - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeFillAttributesCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(fillType), + colour, + static_cast(fillPatternObjectID & 0xFF), + static_cast(fillPatternObjectID >> 8), + 0xFF }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_active_mask(std::uint16_t workingSetObjectID, std::uint16_t newActiveMaskObjectID) const + bool VirtualTerminalClient::send_change_active_mask(std::uint16_t workingSetObjectID, std::uint16_t newActiveMaskObjectID) { - const std::array buffer = { static_cast(Function::ChangeActiveMaskCommand), - static_cast(workingSetObjectID & 0xFF), - static_cast(workingSetObjectID >> 8), - static_cast(newActiveMaskObjectID & 0xFF), - static_cast(newActiveMaskObjectID >> 8), - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeActiveMaskCommand), + static_cast(workingSetObjectID & 0xFF), + static_cast(workingSetObjectID >> 8), + static_cast(newActiveMaskObjectID & 0xFF), + static_cast(newActiveMaskObjectID >> 8), + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_change_softkey_mask(MaskType type, std::uint16_t dataOrAlarmMaskObjectID, std::uint16_t newSoftKeyMaskObjectID) const + bool VirtualTerminalClient::send_change_softkey_mask(MaskType type, std::uint16_t dataOrAlarmMaskObjectID, std::uint16_t newSoftKeyMaskObjectID) { - const std::array buffer = { static_cast(Function::ChangeSoftKeyMaskCommand), - static_cast(type), - static_cast(dataOrAlarmMaskObjectID & 0xFF), - static_cast(dataOrAlarmMaskObjectID >> 8), - static_cast(newSoftKeyMaskObjectID & 0xFF), - static_cast(newSoftKeyMaskObjectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeSoftKeyMaskCommand), + static_cast(type), + static_cast(dataOrAlarmMaskObjectID & 0xFF), + static_cast(dataOrAlarmMaskObjectID >> 8), + static_cast(newSoftKeyMaskObjectID & 0xFF), + static_cast(newSoftKeyMaskObjectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer, true); } - bool VirtualTerminalClient::send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, std::uint32_t value) const + bool VirtualTerminalClient::send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, std::uint32_t value) { - const std::array buffer = { static_cast(Function::ChangeAttributeCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - attributeID, - static_cast(value & 0xFF), - static_cast((value >> 8) & 0xFF), - static_cast((value >> 16) & 0xFF), - static_cast((value >> 24) & 0xFF) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::ChangeAttributeCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + attributeID, + static_cast(value & 0xFF), + static_cast((value >> 8) & 0xFF), + static_cast((value >> 16) & 0xFF), + static_cast((value >> 24) & 0xFF) }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, float value) const + bool VirtualTerminalClient::send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, float value) { static_assert(sizeof(float) == 4, "Float must be 4 bytes"); std::array floatBytes = { 0 }; @@ -646,420 +550,305 @@ namespace isobus std::reverse(floatBytes.begin(), floatBytes.end()); } - const std::array buffer = { static_cast(Function::ChangeAttributeCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - attributeID, - floatBytes[0], - floatBytes[1], - floatBytes[2], - floatBytes[3] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_change_priority(std::uint16_t alarmMaskObjectID, AlarmMaskPriority priority) const - { - const std::array buffer = { static_cast(Function::ChangePriorityCommand), - static_cast(alarmMaskObjectID & 0xFF), - static_cast(alarmMaskObjectID >> 8), - static_cast(priority), - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_change_list_item(std::uint16_t objectID, std::uint8_t listIndex, std::uint16_t newObjectID) const - { - const std::array buffer = { static_cast(Function::ChangeListItemCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - listIndex, - static_cast(newObjectID & 0xFF), - static_cast(newObjectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_lock_unlock_mask(MaskLockState state, std::uint16_t objectID, std::uint16_t timeout_ms) const - { - const std::array buffer = { static_cast(Function::LockUnlockMaskCommand), - static_cast(state), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(timeout_ms & 0xFF), - static_cast(timeout_ms >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_execute_macro(std::uint16_t objectID) const - { - const std::array buffer = { static_cast(Function::ExecuteMacroCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_change_object_label(std::uint16_t objectID, std::uint16_t labelStringObjectID, std::uint8_t fontType, std::uint16_t graphicalDesignatorObjectID) const - { - const std::array buffer = { static_cast(Function::ChangeObjectLabelCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(labelStringObjectID & 0xFF), - static_cast(labelStringObjectID >> 8), - fontType, - static_cast(graphicalDesignatorObjectID & 0xFF), - static_cast(graphicalDesignatorObjectID >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_change_polygon_point(std::uint16_t objectID, std::uint8_t pointIndex, std::uint16_t newXValue, std::uint16_t newYValue) const - { - const std::array buffer = { static_cast(Function::ChangePolygonPointCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - pointIndex, - static_cast(newXValue & 0xFF), - static_cast(newXValue >> 8), - static_cast(newYValue & 0xFF), - static_cast(newYValue >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_change_polygon_scale(std::uint16_t objectID, std::uint16_t widthAttribute, std::uint16_t heightAttribute) const - { - const std::array buffer = { static_cast(Function::ChangePolygonScaleCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(widthAttribute & 0xFF), - static_cast(widthAttribute >> 8), - static_cast(heightAttribute & 0xFF), - static_cast(heightAttribute >> 8), - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_select_colour_map_or_palette(std::uint16_t objectID) const - { - const std::array buffer = { static_cast(Function::SelectColourMapCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_execute_extended_macro(std::uint16_t objectID) const - { - const std::array buffer = { static_cast(Function::ExecuteExtendedMacroCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_select_active_working_set(std::uint64_t NAMEofWorkingSetMasterForDesiredWorkingSet) const - { - const std::array buffer = { static_cast(Function::SelectActiveWorkingSet), - static_cast(NAMEofWorkingSetMasterForDesiredWorkingSet & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 8) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 16) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 24) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 32) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 40) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 48) & 0xFF), - static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 56) & 0xFF) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_graphics_cursor(std::uint16_t objectID, std::int16_t xPosition, std::int16_t yPosition) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetGraphicsCursor), - static_cast(xPosition & 0xFF), - static_cast(xPosition >> 8), - static_cast(yPosition & 0xFF), - static_cast(yPosition >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_move_graphics_cursor(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::MoveGraphicsCursor), - static_cast(xOffset & 0xFF), - static_cast(xOffset >> 8), - static_cast(yOffset & 0xFF), - static_cast(yOffset >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_foreground_colour(std::uint16_t objectID, std::uint8_t colour) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetForegroundColour), - colour, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_background_colour(std::uint16_t objectID, std::uint8_t colour) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetBackgroundColour), - colour, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_line_attributes_object_id(std::uint16_t objectID, std::uint16_t lineAttributesObjectID) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetLineAttributesObjectID), - static_cast(lineAttributesObjectID & 0xFF), - static_cast(lineAttributesObjectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_fill_attributes_object_id(std::uint16_t objectID, std::uint16_t fillAttributesObjectID) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetFillAttributesObjectID), - static_cast(fillAttributesObjectID & 0xFF), - static_cast(fillAttributesObjectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_set_font_attributes_object_id(std::uint16_t objectID, std::uint16_t fontAttributesObjectID) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::SetFontAttributesObjectID), - static_cast(fontAttributesObjectID & 0xFF), - static_cast(fontAttributesObjectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_erase_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::EraseRectangle), - static_cast(width & 0xFF), - static_cast(width >> 8), - static_cast(height & 0xFF), - static_cast(height >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_draw_point(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::DrawPoint), - static_cast(xOffset & 0xFF), - static_cast(xOffset >> 8), - static_cast(yOffset & 0xFF), - static_cast(yOffset >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_draw_line(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::DrawLine), - static_cast(xOffset & 0xFF), - static_cast(xOffset >> 8), - static_cast(yOffset & 0xFF), - static_cast(yOffset >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_draw_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::DrawRectangle), - static_cast(width & 0xFF), - static_cast(width >> 8), - static_cast(height & 0xFF), - static_cast(height >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_draw_closed_ellipse(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::DrawClosedEllipse), - static_cast(width & 0xFF), - static_cast(width >> 8), - static_cast(height & 0xFF), - static_cast(height >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_draw_polygon(std::uint16_t objectID, std::uint8_t numberOfPoints, std::int16_t *listOfXOffsetsRelativeToCursor, std::int16_t *listOfYOffsetsRelativeToCursor) const + const std::vector buffer = { static_cast(Function::ChangeAttributeCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + attributeID, + floatBytes[0], + floatBytes[1], + floatBytes[2], + floatBytes[3] }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_change_priority(std::uint16_t alarmMaskObjectID, AlarmMaskPriority priority) + { + const std::vector buffer = { static_cast(Function::ChangePriorityCommand), + static_cast(alarmMaskObjectID & 0xFF), + static_cast(alarmMaskObjectID >> 8), + static_cast(priority), + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_change_list_item(std::uint16_t objectID, std::uint8_t listIndex, std::uint16_t newObjectID) + { + const std::vector buffer = { static_cast(Function::ChangeListItemCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + listIndex, + static_cast(newObjectID & 0xFF), + static_cast(newObjectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_lock_unlock_mask(MaskLockState state, std::uint16_t objectID, std::uint16_t timeout_ms) + { + const std::vector buffer = { static_cast(Function::LockUnlockMaskCommand), + static_cast(state), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(timeout_ms & 0xFF), + static_cast(timeout_ms >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer, true); + } + + bool VirtualTerminalClient::send_execute_macro(std::uint16_t objectID) + { + const std::vector buffer = { static_cast(Function::ExecuteMacroCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_change_object_label(std::uint16_t objectID, std::uint16_t labelStringObjectID, std::uint8_t fontType, std::uint16_t graphicalDesignatorObjectID) + { + const std::vector buffer = { static_cast(Function::ChangeObjectLabelCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(labelStringObjectID & 0xFF), + static_cast(labelStringObjectID >> 8), + fontType, + static_cast(graphicalDesignatorObjectID & 0xFF), + static_cast(graphicalDesignatorObjectID >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_change_polygon_point(std::uint16_t objectID, std::uint8_t pointIndex, std::uint16_t newXValue, std::uint16_t newYValue) + { + const std::vector buffer = { static_cast(Function::ChangePolygonPointCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + pointIndex, + static_cast(newXValue & 0xFF), + static_cast(newXValue >> 8), + static_cast(newYValue & 0xFF), + static_cast(newYValue >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_change_polygon_scale(std::uint16_t objectID, std::uint16_t widthAttribute, std::uint16_t heightAttribute) + { + const std::vector buffer = { static_cast(Function::ChangePolygonScaleCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(widthAttribute & 0xFF), + static_cast(widthAttribute >> 8), + static_cast(heightAttribute & 0xFF), + static_cast(heightAttribute >> 8), + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_select_colour_map_or_palette(std::uint16_t objectID) + { + const std::vector buffer = { static_cast(Function::SelectColourMapCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); + } + + bool VirtualTerminalClient::send_execute_extended_macro(std::uint16_t objectID) + { + const std::vector buffer = { static_cast(Function::ExecuteExtendedMacroCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_select_active_working_set(std::uint64_t NAMEofWorkingSetMasterForDesiredWorkingSet) + { + const std::vector buffer = { static_cast(Function::SelectActiveWorkingSet), + static_cast(NAMEofWorkingSetMasterForDesiredWorkingSet & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 8) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 16) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 24) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 32) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 40) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 48) & 0xFF), + static_cast((NAMEofWorkingSetMasterForDesiredWorkingSet >> 56) & 0xFF) }; + return queue_command(buffer, true); + } + + bool VirtualTerminalClient::send_set_graphics_cursor(std::uint16_t objectID, std::int16_t xPosition, std::int16_t yPosition) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetGraphicsCursor), + static_cast(xPosition & 0xFF), + static_cast(xPosition >> 8), + static_cast(yPosition & 0xFF), + static_cast(yPosition >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_move_graphics_cursor(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::MoveGraphicsCursor), + static_cast(xOffset & 0xFF), + static_cast(xOffset >> 8), + static_cast(yOffset & 0xFF), + static_cast(yOffset >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_set_foreground_colour(std::uint16_t objectID, std::uint8_t colour) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetForegroundColour), + colour, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_set_background_colour(std::uint16_t objectID, std::uint8_t colour) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetBackgroundColour), + colour, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_set_line_attributes_object_id(std::uint16_t objectID, std::uint16_t lineAttributesObjectID) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetLineAttributesObjectID), + static_cast(lineAttributesObjectID & 0xFF), + static_cast(lineAttributesObjectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_set_fill_attributes_object_id(std::uint16_t objectID, std::uint16_t fillAttributesObjectID) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetFillAttributesObjectID), + static_cast(fillAttributesObjectID & 0xFF), + static_cast(fillAttributesObjectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_set_font_attributes_object_id(std::uint16_t objectID, std::uint16_t fontAttributesObjectID) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::SetFontAttributesObjectID), + static_cast(fontAttributesObjectID & 0xFF), + static_cast(fontAttributesObjectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_erase_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::EraseRectangle), + static_cast(width & 0xFF), + static_cast(width >> 8), + static_cast(height & 0xFF), + static_cast(height >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_draw_point(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::DrawPoint), + static_cast(xOffset & 0xFF), + static_cast(xOffset >> 8), + static_cast(yOffset & 0xFF), + static_cast(yOffset >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_draw_line(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::DrawLine), + static_cast(xOffset & 0xFF), + static_cast(xOffset >> 8), + static_cast(yOffset & 0xFF), + static_cast(yOffset >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_draw_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::DrawRectangle), + static_cast(width & 0xFF), + static_cast(width >> 8), + static_cast(height & 0xFF), + static_cast(height >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_draw_closed_ellipse(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::DrawClosedEllipse), + static_cast(width & 0xFF), + static_cast(width >> 8), + static_cast(height & 0xFF), + static_cast(height >> 8) }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_draw_polygon(std::uint16_t objectID, std::uint8_t numberOfPoints, const std::int16_t *listOfXOffsetsRelativeToCursor, const std::int16_t *listOfYOffsetsRelativeToCursor) { bool retVal = false; @@ -1083,17 +872,12 @@ namespace isobus buffer[7 + i] = static_cast(listOfYOffsetsRelativeToCursor[0] & 0xFF); buffer[8 + i] = static_cast((listOfYOffsetsRelativeToCursor[0] >> 8) & 0xFF); } - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + retVal = queue_command(buffer); } return retVal; } - bool VirtualTerminalClient::send_draw_text(std::uint16_t objectID, bool transparent, std::uint8_t textLength, const char *value) const + bool VirtualTerminalClient::send_draw_text(std::uint16_t objectID, bool transparent, std::uint8_t textLength, const char *value) { bool retVal = false; @@ -1115,35 +899,25 @@ namespace isobus { buffer.push_back(0xFF); // Pad short text to minimum message length } - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + retVal = queue_command(buffer); } return retVal; } - bool VirtualTerminalClient::send_pan_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute) const + bool VirtualTerminalClient::send_pan_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute) { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::PanViewport), - static_cast(xAttribute & 0xFF), - static_cast(xAttribute >> 8), - static_cast(yAttribute & 0xFF), - static_cast(yAttribute >> 8) }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::PanViewport), + static_cast(xAttribute & 0xFF), + static_cast(xAttribute >> 8), + static_cast(yAttribute & 0xFF), + static_cast(yAttribute >> 8) }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_zoom_viewport(std::uint16_t objectID, float zoom) const + bool VirtualTerminalClient::send_zoom_viewport(std::uint16_t objectID, float zoom) { static_assert(sizeof(float) == 4, "Float must be 4 bytes"); std::array floatBytes = { 0 }; @@ -1154,23 +928,18 @@ namespace isobus std::reverse(floatBytes.begin(), floatBytes.end()); } - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::ZoomViewport), - floatBytes[0], - floatBytes[1], - floatBytes[2], - floatBytes[3] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::ZoomViewport), + floatBytes[0], + floatBytes[1], + floatBytes[2], + floatBytes[3] }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_pan_and_zoom_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute, float zoom) const + bool VirtualTerminalClient::send_pan_and_zoom_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute, float zoom) { static_assert(sizeof(float) == 4, "Float must be 4 bytes"); std::array floatBytes = { 0 }; @@ -1181,27 +950,22 @@ namespace isobus std::reverse(floatBytes.begin(), floatBytes.end()); } - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::PanAndZoomViewport), - static_cast(xAttribute & 0xFF), - static_cast(xAttribute >> 8), - static_cast(yAttribute & 0xFF), - static_cast(yAttribute >> 8), - floatBytes[0], - floatBytes[1], - floatBytes[2], - floatBytes[3] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::PanAndZoomViewport), + static_cast(xAttribute & 0xFF), + static_cast(xAttribute >> 8), + static_cast(yAttribute & 0xFF), + static_cast(yAttribute >> 8), + floatBytes[0], + floatBytes[1], + floatBytes[2], + floatBytes[3] }; + return queue_command(buffer); } - bool VirtualTerminalClient::send_change_viewport_size(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const + bool VirtualTerminalClient::send_change_viewport_size(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) { constexpr std::uint16_t MAX_WIDTH_HEIGHT = 32767; bool retVal = false; @@ -1209,94 +973,69 @@ namespace isobus if ((width <= MAX_WIDTH_HEIGHT) && (height <= MAX_WIDTH_HEIGHT)) { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - static_cast(GraphicsContextSubCommandID::ChangeViewportSize), - static_cast(width & 0xFF), - static_cast(width >> 8), - static_cast(height & 0xFF), - static_cast(height >> 8) }; - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + static_cast(GraphicsContextSubCommandID::ChangeViewportSize), + static_cast(width & 0xFF), + static_cast(width >> 8), + static_cast(height & 0xFF), + static_cast(height >> 8) }; + retVal = queue_command(buffer); } return retVal; } - bool VirtualTerminalClient::send_draw_vt_object(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(graphicsContextObjectID & 0xFF), - static_cast(graphicsContextObjectID >> 8), - static_cast(GraphicsContextSubCommandID::DrawVTObject), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_copy_canvas_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) const - { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(graphicsContextObjectID & 0xFF), - static_cast(graphicsContextObjectID >> 8), - static_cast(GraphicsContextSubCommandID::CopyCanvasToPictureGraphic), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_copy_viewport_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) const + bool VirtualTerminalClient::send_draw_vt_object(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) { - const std::array buffer = { static_cast(Function::GraphicsContextCommand), - static_cast(graphicsContextObjectID & 0xFF), - static_cast(graphicsContextObjectID >> 8), - static_cast(GraphicsContextSubCommandID::CopyViewportToPictureGraphic), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); - } - - bool VirtualTerminalClient::send_get_attribute_value(std::uint16_t objectID, std::uint8_t attributeID) const - { - const std::array buffer = { static_cast(Function::GetAttributeValueMessage), - static_cast(objectID & 0xFF), - static_cast(objectID >> 8), - attributeID, - 0xFF, - 0xFF, - 0xFF, - 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(graphicsContextObjectID & 0xFF), + static_cast(graphicsContextObjectID >> 8), + static_cast(GraphicsContextSubCommandID::DrawVTObject), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_copy_canvas_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(graphicsContextObjectID & 0xFF), + static_cast(graphicsContextObjectID >> 8), + static_cast(GraphicsContextSubCommandID::CopyCanvasToPictureGraphic), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_copy_viewport_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) + { + const std::vector buffer = { static_cast(Function::GraphicsContextCommand), + static_cast(graphicsContextObjectID & 0xFF), + static_cast(graphicsContextObjectID >> 8), + static_cast(GraphicsContextSubCommandID::CopyViewportToPictureGraphic), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + 0xFF, + 0xFF }; + return queue_command(buffer); + } + + bool VirtualTerminalClient::send_get_attribute_value(std::uint16_t objectID, std::uint8_t attributeID) + { + const std::vector buffer = { static_cast(Function::GetAttributeValueMessage), + static_cast(objectID & 0xFF), + static_cast(objectID >> 8), + attributeID, + 0xFF, + 0xFF, + 0xFF, + 0xFF }; + return queue_command(buffer, true); } std::uint8_t VirtualTerminalClient::get_softkey_x_axis_pixels() const @@ -1458,7 +1197,7 @@ namespace isobus return retVal; } - bool VirtualTerminalClient::get_vt_version_supported(VTVersion minimumVersion) const + bool VirtualTerminalClient::is_vt_version_supported(VTVersion minimumVersion) const { bool retVal = false; @@ -1480,7 +1219,7 @@ namespace isobus return activeWorkingSetSoftKeyMaskObjectID; } - void VirtualTerminalClient::set_object_pool(std::uint8_t poolIndex, VTVersion poolSupportedVTVersion, const std::uint8_t *pool, std::uint32_t size, std::string version) + void VirtualTerminalClient::set_object_pool(std::uint8_t poolIndex, const std::uint8_t *pool, std::uint32_t size, std::string version) { if ((nullptr != pool) && (0 != size)) @@ -1493,7 +1232,6 @@ namespace isobus tempData.objectPoolSize = size; tempData.autoScaleDataMaskOriginalDimension = 0; tempData.autoScaleSoftKeyDesignatorOriginalHeight = 0; - tempData.version = poolSupportedVTVersion; tempData.useDataCallback = false; tempData.uploaded = false; tempData.versionLabel = version; @@ -1510,7 +1248,7 @@ namespace isobus } } - void VirtualTerminalClient::set_object_pool(std::uint8_t poolIndex, VTVersion poolSupportedVTVersion, const std::vector *pool, std::string version) + void VirtualTerminalClient::set_object_pool(std::uint8_t poolIndex, const std::vector *pool, std::string version) { if ((nullptr != pool) && (0 != pool->size())) @@ -1523,7 +1261,6 @@ namespace isobus tempData.objectPoolSize = pool->size(); tempData.autoScaleDataMaskOriginalDimension = 0; tempData.autoScaleSoftKeyDesignatorOriginalHeight = 0; - tempData.version = poolSupportedVTVersion; tempData.useDataCallback = false; tempData.uploaded = false; tempData.versionLabel = version; @@ -1550,7 +1287,7 @@ namespace isobus objectPools[poolIndex].autoScaleSoftKeyDesignatorOriginalHeight = originalSoftKyeDesignatorHeight_px; } - void VirtualTerminalClient::register_object_pool_data_chunk_callback(std::uint8_t poolIndex, VTVersion poolSupportedVTVersion, std::uint32_t poolTotalSize, DataChunkCallback value, std::string version) + void VirtualTerminalClient::register_object_pool_data_chunk_callback(std::uint8_t poolIndex, std::uint32_t poolTotalSize, DataChunkCallback value, std::string version) { if ((nullptr != value) && (0 != poolTotalSize)) @@ -1561,7 +1298,6 @@ namespace isobus tempData.objectPoolVectorPointer = nullptr; tempData.dataCallback = value; tempData.objectPoolSize = poolTotalSize; - tempData.version = poolSupportedVTVersion; tempData.useDataCallback = true; tempData.uploaded = false; tempData.autoScaleSoftKeyDesignatorOriginalHeight = 0; @@ -1592,6 +1328,7 @@ namespace isobus { sendWorkingSetMaintenance = false; sendAuxiliaryMaintenance = false; + unsupportedFunctions.clear(); if (partnerControlFunction->get_address_valid()) { @@ -1625,14 +1362,14 @@ namespace isobus // so the state machine cannot progress. if (SystemTiming::time_expired_ms(lastVTStatusTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Ready to upload pool, but VT server has timed out. Disconnecting."); + CANStackLogger::error("[VT]: Ready to upload pool, but VT server has timed out. Disconnecting."); set_state(StateMachineState::Disconnected); } if (0 != objectPools.size()) { set_state(StateMachineState::SendGetMemory); - send_working_set_maintenance(true, objectPools[0].version); + send_working_set_maintenance(true); lastWorkingSetMaintenanceTimestamp_ms = SystemTiming::get_timestamp_ms(); sendWorkingSetMaintenance = true; sendAuxiliaryMaintenance = true; @@ -1661,7 +1398,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Memory Response Timeout"); + CANStackLogger::error("[VT]: Get Memory Response Timeout"); } } break; @@ -1680,7 +1417,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Number Softkeys Response Timeout"); + CANStackLogger::error("[VT]: Get Number Softkeys Response Timeout"); } } break; @@ -1699,7 +1436,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Text Font Data Response Timeout"); + CANStackLogger::error("[VT]: Get Text Font Data Response Timeout"); } } break; @@ -1718,7 +1455,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Hardware Response Timeout"); + CANStackLogger::error("[VT]: Get Hardware Response Timeout"); } } break; @@ -1728,7 +1465,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Versions Timeout"); + CANStackLogger::error("[VT]: Get Versions Timeout"); } else if ((!objectPools.empty()) && (!objectPools[0].versionLabel.empty()) && @@ -1744,7 +1481,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get Versions Response Timeout"); + CANStackLogger::error("[VT]: Get Versions Response Timeout"); } } break; @@ -1754,7 +1491,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Send Load Version Timeout"); + CANStackLogger::error("[VT]: Send Load Version Timeout"); } else { @@ -1788,7 +1525,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Load Version Response Timeout"); + CANStackLogger::error("[VT]: Load Version Response Timeout"); } } break; @@ -1798,7 +1535,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Send Store Version Timeout"); + CANStackLogger::error("[VT]: Send Store Version Timeout"); } else { @@ -1832,7 +1569,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Store Version Response Timeout"); + CANStackLogger::error("[VT]: Store Version Response Timeout"); } } break; @@ -1873,7 +1610,7 @@ namespace isobus objectPools[i].objectPoolSize + 1, // Account for Mux byte myControlFunction, partnerControlFunction, - CANIdentifier::CANPriority::PriorityLowest7, + CANIdentifier::CANPriority::Priority5, process_callback, this, process_internal_object_pool_upload_callback); @@ -1890,24 +1627,29 @@ namespace isobus } else if (CurrentObjectPoolUploadState::Success == currentObjectPoolState) { - objectPools[i].uploaded = true; - currentObjectPoolState = CurrentObjectPoolUploadState::Uninitialized; + if (false == objectPools[i].uploaded) + { + objectPools[i].uploaded = true; + CANStackLogger::debug("[VT]: Object pool %u uploaded.", i + 1); + currentObjectPoolState = CurrentObjectPoolUploadState::Uninitialized; + } } else if (CurrentObjectPoolUploadState::Failed == currentObjectPoolState) { currentObjectPoolState = CurrentObjectPoolUploadState::Uninitialized; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: An object pool failed to upload. Resetting connection to VT."); + CANStackLogger::error("[VT]: An object pool failed to upload. Resetting connection to VT."); set_state(StateMachineState::Disconnected); } else { // Transfer is in progress. Nothing to do now. + allPoolsProcessed = false; break; } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: An object pool was supplied with an invalid size or pointer. Ignoring it."); + CANStackLogger::warn("[VT]: An object pool was supplied with an invalid size or pointer. Ignoring it."); objectPools[i].uploaded = true; } } @@ -1933,7 +1675,7 @@ namespace isobus if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Get End of Object Pool Response Timeout"); + CANStackLogger::error("[VT]: Get End of Object Pool Response Timeout"); } } break; @@ -1944,7 +1686,7 @@ namespace isobus if (SystemTiming::time_expired_ms(lastVTStatusTimestamp_ms, VT_STATUS_TIMEOUT_MS)) { set_state(StateMachineState::Disconnected); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Status Timeout"); + CANStackLogger::error("[VT]: Status Timeout"); } update_auxiliary_input_status(); } @@ -1959,7 +1701,7 @@ namespace isobus // Retry connecting after a while if (SystemTiming::time_expired_ms(stateMachineTimestamp_ms, VT_STATE_MACHINE_RETRY_TIMEOUT_MS)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: Resetting Failed VT Connection"); + CANStackLogger::info("[VT]: Resetting Failed VT Connection"); set_state(StateMachineState::Disconnected); } } @@ -1989,6 +1731,7 @@ namespace isobus txFlags.set_flag(static_cast(TransmitFlags::SendAuxiliaryMaintenance)); } txFlags.process_all_flags(); + process_command_queue(); if (state == previousStateMachineState) { @@ -1996,6 +1739,16 @@ namespace isobus } } + bool VirtualTerminalClient::send_message_to_vt(const std::uint8_t *dataBuffer, std::uint32_t dataLength, CANIdentifier::CANPriority priority) const + { + return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), + dataBuffer, + dataLength, + myControlFunction, + partnerControlFunction, + priority); + } + bool VirtualTerminalClient::send_delete_object_pool() const { constexpr std::array buffer = { static_cast(Function::DeleteObjectPoolCommand), @@ -2006,66 +1759,24 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } - bool VirtualTerminalClient::send_working_set_maintenance(bool initializing, VTVersion workingSetVersion) const + bool VirtualTerminalClient::send_working_set_maintenance(bool initializing) const { - std::uint8_t versionByte; - std::uint8_t bitmask = (initializing ? 0x01 : 0x00); - - switch (workingSetVersion) - { - case VTVersion::Version3: - { - versionByte = 0x03; - } - break; - - case VTVersion::Version4: - { - versionByte = 0x04; - } - break; - - case VTVersion::Version5: - { - versionByte = 0x05; - } - break; - - case VTVersion::Version6: - { - versionByte = 0x06; - } - break; + static constexpr std::uint8_t SUPPORTED_VT_VERSION = 0x06; - default: - { - versionByte = 0xFF; - } - break; - } + std::uint8_t bitmask = (initializing ? 0x01 : 0x00); const std::array buffer = { static_cast(Function::WorkingSetMaintenanceMessage), bitmask, - versionByte, + SUPPORTED_VT_VERSION, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_memory(std::uint32_t requiredMemory) const @@ -2078,12 +1789,7 @@ namespace isobus static_cast((requiredMemory >> 24) & 0xFF), 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_number_of_softkeys() const @@ -2096,12 +1802,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_text_font_data() const @@ -2114,12 +1815,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_hardware() const @@ -2132,12 +1828,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_supported_widechars() const @@ -2150,12 +1841,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_window_mask_data() const @@ -2168,12 +1854,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_supported_objects() const @@ -2186,12 +1867,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_get_versions() const @@ -2204,12 +1880,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_store_version(std::array versionLabel) const @@ -2222,12 +1893,7 @@ namespace isobus versionLabel[4], versionLabel[5], versionLabel[6] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_load_version(std::array versionLabel) const @@ -2240,12 +1906,7 @@ namespace isobus versionLabel[4], versionLabel[5], versionLabel[6] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_delete_version(std::array versionLabel) const @@ -2258,12 +1919,7 @@ namespace isobus versionLabel[4], versionLabel[5], versionLabel[6] }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_extended_get_versions() const @@ -2276,12 +1932,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_extended_store_version(std::array versionLabel) const @@ -2289,12 +1940,7 @@ namespace isobus std::array buffer; buffer[0] = static_cast(Function::ExtendedStoreVersionCommand); memcpy(&buffer[1], versionLabel.data(), 32); - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_extended_load_version(std::array versionLabel) const @@ -2302,12 +1948,7 @@ namespace isobus std::array buffer; buffer[0] = static_cast(Function::ExtendedLoadVersionCommand); memcpy(&buffer[1], versionLabel.data(), 32); - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_extended_delete_version(std::array versionLabel) const @@ -2315,12 +1956,7 @@ namespace isobus std::array buffer; buffer[0] = static_cast(Function::ExtendedDeleteVersionCommand); memcpy(&buffer[1], versionLabel.data(), 32); - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_end_of_object_pool() const @@ -2333,12 +1969,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_working_set_master() const @@ -2356,7 +1987,7 @@ namespace isobus CAN_DATA_LENGTH, myControlFunction, nullptr, - CANIdentifier::PriorityLowest7); + CANIdentifier::CANPriority::Priority5); } bool VirtualTerminalClient::send_auxiliary_functions_preferred_assignment() const @@ -2367,12 +1998,7 @@ namespace isobus { buffer.resize(CAN_DATA_LENGTH); } - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - buffer.size(), - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_auxiliary_function_assignment_response(std::uint16_t functionObjectID, bool hasError, bool isAlreadyAssigned) const @@ -2382,7 +2008,7 @@ namespace isobus { errorCode |= 0x01; } - if ((isAlreadyAssigned) && (false == get_vt_version_supported(VTVersion::Version6))) + if ((isAlreadyAssigned) && (false == is_vt_version_supported(VTVersion::Version6))) { errorCode |= 0x02; } @@ -2394,12 +2020,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } bool VirtualTerminalClient::send_auxiliary_input_maintenance() const @@ -2417,7 +2038,7 @@ namespace isobus CAN_DATA_LENGTH, myControlFunction, nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } bool VirtualTerminalClient::send_auxiliary_input_status_enable_response(std::uint16_t objectID, bool isEnabled, bool invalidObjectID) const @@ -2430,12 +2051,7 @@ namespace isobus 0xFF, 0xFF, 0xFF }; - return CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::PriorityLowest7); + return send_message_to_vt(buffer.data(), buffer.size()); } void VirtualTerminalClient::update_auxiliary_input_status() @@ -2488,12 +2104,7 @@ namespace isobus operatingState }; if (get_auxiliary_input_learn_mode_enabled()) { - retVal = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), - buffer.data(), - CAN_DATA_LENGTH, - myControlFunction, - partnerControlFunction, - CANIdentifier::Priority3); + retVal = send_message_to_vt(buffer.data(), buffer.size(), CANIdentifier::CANPriority::Priority3); } else { @@ -2502,7 +2113,7 @@ namespace isobus CAN_DATA_LENGTH, myControlFunction, nullptr, - CANIdentifier::Priority3); + CANIdentifier::CANPriority::Priority3); } } return retVal; @@ -2544,7 +2155,7 @@ namespace isobus { if (!vtClient->objectPools.empty()) { - transmitSuccessful = vtClient->send_working_set_maintenance(false, vtClient->objectPools[0].version); + transmitSuccessful = vtClient->send_working_set_maintenance(false); if (transmitSuccessful) { @@ -2596,7 +2207,7 @@ namespace isobus std::uint32_t targetParameterGroupNumber = message.get_uint24_at(5); if (static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal) == targetParameterGroupNumber) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: The VT Server is NACK-ing our VT messages. Disconnecting."); + CANStackLogger::error("[VT]: The VT Server is NACK-ing our VT messages. Disconnecting."); parentVT->set_state(StateMachineState::Disconnected); } } @@ -2615,12 +2226,30 @@ namespace isobus std::uint16_t objectID = message.get_uint16_at(2); std::uint16_t parentObjectID = message.get_uint16_at(4); std::uint8_t keyNumber = message.get_uint8_at(6); - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + transactionNumber = message.get_uint8_at(7) >> 4; } parentVT->softKeyEventDispatcher.invoke({ parentVT, objectID, parentObjectID, keyNumber, static_cast(keyCode) }); + + // Send response + std::array buffer{ + static_cast(Function::SoftKeyActivationMessage), + keyCode, + static_cast(objectID), + static_cast(objectID >> 8), + static_cast(parentObjectID), + static_cast(parentObjectID >> 8), + keyNumber, + 0xFF, + }; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + buffer[7] = static_cast(transactionNumber << 4 | 0x0F); + } + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } } break; @@ -2633,11 +2262,30 @@ namespace isobus std::uint16_t objectID = message.get_uint16_at(2); std::uint16_t parentObjectID = message.get_uint16_at(4); std::uint8_t keyNumber = message.get_uint8_at(6); - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + transactionNumber = message.get_uint8_at(7) >> 4; } + parentVT->buttonEventDispatcher.invoke({ parentVT, objectID, parentObjectID, keyNumber, static_cast(keyCode) }); + + // Send response + std::array buffer{ + static_cast(Function::ButtonActivationMessage), + keyCode, + static_cast(objectID), + static_cast(objectID >> 8), + static_cast(parentObjectID), + static_cast(parentObjectID >> 8), + keyNumber, + 0xFF, + }; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + buffer[7] = static_cast(transactionNumber << 4 | 0x0F); + } + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } } break; @@ -2649,14 +2297,15 @@ namespace isobus std::uint8_t touchState = static_cast(KeyActivationCode::ButtonPressedOrLatched); std::uint16_t parentMaskObjectID = NULL_OBJECT_ID; - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - // VT version is at least 6 + // VT version is 6 or later touchState = message.get_uint8_at(5) & 0x0F; + transactionNumber = message.get_uint8_at(5) >> 4; parentMaskObjectID = message.get_uint16_at(6); - //! @todo process TAN } - else if (parentVT->get_vt_version_supported(VTVersion::Version4)) + else if (parentVT->is_vt_version_supported(VTVersion::Version4)) { // VT version is either 4 or 5 touchState = message.get_uint8_at(5); @@ -2666,6 +2315,29 @@ namespace isobus { parentVT->pointingEventDispatcher.invoke({ parentVT, xPosition, yPosition, parentMaskObjectID, static_cast(touchState) }); } + + // Send response + std::array buffer{ + static_cast(Function::PointingEventMessage), + static_cast(xPosition), + static_cast(xPosition >> 8), + static_cast(yPosition), + static_cast(yPosition >> 8), + 0xFF, + 0xFF, + 0xFF, + }; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + // VT version is 6 or later + buffer[5] = static_cast((transactionNumber << 4) | touchState); + } + if (parentVT->is_vt_version_supported(VTVersion::Version4)) + { + // VT version is either 4 or 5 + buffer[5] = touchState; + } + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2675,17 +2347,41 @@ namespace isobus bool objectSelected = (0x01 == message.get_uint8_at(3)); bool objectOpenForInput = true; - if (parentVT->get_vt_version_supported(VTVersion::Version4)) + if (parentVT->is_vt_version_supported(VTVersion::Version4)) { objectOpenForInput = message.get_bool_at(4, 0); } - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + transactionNumber = message.get_uint8_at(7) >> 4; } parentVT->selectInputObjectEventDispatcher.invoke({ parentVT, objectID, objectSelected, objectOpenForInput }); + + // Send response + std::array buffer{ + static_cast(Function::VTSelectInputObjectMessage), + static_cast(objectID), + static_cast(objectID >> 8), + static_cast(objectSelected ? 0x01 : 0x00), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + }; + + if (parentVT->is_vt_version_supported(VTVersion::Version4)) + { + buffer[4] = (objectOpenForInput ? 0x01 : 0x00); + } + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + buffer[7] = static_cast(transactionNumber << 4 | 0x0F); + } + + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2696,12 +2392,27 @@ namespace isobus if ((errorCode == static_cast(ESCMessageErrorCode::OtherError)) || (errorCode <= static_cast(ESCMessageErrorCode::NoInputFieldOpen))) { - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + // VT version is 6 or later + transactionNumber = message.get_uint8_at(7) >> 4; } parentVT->escMessageEventDispatcher.invoke({ parentVT, objectID, static_cast(errorCode) }); + + // Send response + std::array buffer{ + static_cast(Function::VTESCMessage), + static_cast(objectID), + static_cast(objectID >> 8), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + static_cast((transactionNumber << 4) | 0x0F), + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } } break; @@ -2710,12 +2421,31 @@ namespace isobus { std::uint16_t objectID = message.get_uint16_at(1); std::uint32_t value = message.get_uint32_at(4); - - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + // VT version is 6 or later + transactionNumber = message.get_uint8_at(7) >> 4; } + parentVT->changeNumericValueEventDispatcher.invoke({ parentVT, value, objectID }); + + // Send response + std::array buffer{ + static_cast(Function::VTChangeNumericValueMessage), + static_cast(objectID), + static_cast(objectID >> 8), + 0xFF, + static_cast(value), + static_cast(value >> 8), + static_cast(value >> 16), + static_cast(value >> 24), + }; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + buffer[3] = static_cast(transactionNumber << 4 | 0x0F); + } + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2739,6 +2469,19 @@ namespace isobus maskOrChildHasErrors, anyOtherError, poolDeleted }); + + // Send response + std::array buffer{ + static_cast(Function::VTChangeActiveMaskMessage), + static_cast(maskObjectID), + static_cast(maskObjectID >> 8), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2759,6 +2502,19 @@ namespace isobus maskOrChildHasErrors, anyOtherError, poolDeleted }); + + // Send response + std::array buffer{ + static_cast(Function::VTChangeSoftKeyMaskMessage), + static_cast(dataOrAlarmMaskID), + static_cast(dataOrAlarmMaskID >> 8), + static_cast(softKeyMaskID), + static_cast(softKeyMaskID >> 8), + 0xFF, + 0xFF, + 0xFF + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2769,6 +2525,19 @@ namespace isobus std::string value = std::string(message.get_data().begin() + 4, message.get_data().begin() + 4 + stringLength); parentVT->changeStringValueEventDispatcher.invoke({ value, parentVT, objectID }); + + // Send response + std::array buffer{ + static_cast(Function::VTChangeStringValueMessage), + 0xFF, + 0xFF, + static_cast(objectID), + static_cast(objectID >> 8), + 0xFF, + 0xFF, + 0xFF + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2787,10 +2556,21 @@ namespace isobus parentVT->userLayoutHideShowEventDispatcher.invoke({ parentVT, objectID, hidden }); } - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + // Send response + std::array buffer; + std::copy_n(message.get_data().begin(), CAN_DATA_LENGTH, buffer.begin()); + // Make sure we comply with standard specifications + if (parentVT->is_vt_version_supported(VTVersion::Version6)) + { + // VT version is 6 or later + buffer[7] |= 0x0F; + } + else { - //! @todo process TAN + // VT version is 5 or prior + buffer[7] = 0xFF; } + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } break; @@ -2800,9 +2580,22 @@ namespace isobus parentVT->audioSignalTerminationEventDispatcher.invoke({ parentVT, terminated }); - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + std::uint8_t transactionNumber = 0xF; + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { - //! @todo process TAN + // VT version is 6 or later, send response (VT version 5 and prior does not have a response) + transactionNumber = message.get_uint8_at(2) >> 4; + std::array buffer{ + static_cast(Function::VTControlAudioSignalTerminationMessage), + static_cast(terminated ? 0x01 : 0x00), + static_cast((transactionNumber << 4) | 0x0F), + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); } } break; @@ -2811,33 +2604,33 @@ namespace isobus { if (message.get_bool_at(1, 0)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Preferred Assignment Error - Auxiliary Input Unit(s) (NAME or Model Identification Code) not valid"); + CANStackLogger::error("[AUX-N]: Preferred Assignment Error - Auxiliary Input Unit(s) (NAME or Model Identification Code) not valid"); } if (message.get_bool_at(1, 1)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Preferred Assignment Error - Function Object ID(S) not valid"); + CANStackLogger::error("[AUX-N]: Preferred Assignment Error - Function Object ID(S) not valid"); } if (message.get_bool_at(1, 2)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Preferred Assignment Error - Input Object ID(s) not valid"); + CANStackLogger::error("[AUX-N]: Preferred Assignment Error - Input Object ID(s) not valid"); } if (message.get_bool_at(1, 3)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Preferred Assignment Error - Duplicate Object ID of Auxiliary Function"); + CANStackLogger::error("[AUX-N]: Preferred Assignment Error - Duplicate Object ID of Auxiliary Function"); } if (message.get_bool_at(1, 4)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Preferred Assignment Error - Other"); + CANStackLogger::error("[AUX-N]: Preferred Assignment Error - Other"); } if (0 != message.get_uint8_at(1)) { std::uint16_t faultyObjectID = message.get_uint16_at(2); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[AUX-N]: Auxiliary Function Object ID of faulty assignment: " + isobus::to_string(faultyObjectID)); + CANStackLogger::error("[AUX-N]: Auxiliary Function Object ID of faulty assignment: " + isobus::to_string(faultyObjectID)); } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[AUX-N]: Preferred Assignment OK"); + CANStackLogger::debug("[AUX-N]: Preferred Assignment OK"); //! @todo load the preferred assignment into parentVT->assignedAuxiliaryInputDevices } } @@ -2863,7 +2656,7 @@ namespace isobus { aux.functions.clear(); } - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[AUX-N] Unassigned all functions"); + CANStackLogger::info("[AUX-N] Unassigned all functions"); } else if (NULL_OBJECT_ID == inputObjectID) { @@ -2878,7 +2671,7 @@ namespace isobus { //! @todo save preferred assignment to persistent configuration } - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[AUX-N] Unassigned function " + isobus::to_string(static_cast(functionObjectID)) + " from input " + isobus::to_string(static_cast(inputObjectID))); + CANStackLogger::info("[AUX-N] Unassigned function " + isobus::to_string(static_cast(functionObjectID)) + " from input " + isobus::to_string(static_cast(inputObjectID))); } else { @@ -2906,32 +2699,32 @@ namespace isobus { //! @todo save preferred assignment to persistent configuration } - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[AUX-N]: Assigned function " + isobus::to_string(static_cast(functionObjectID)) + " to input " + isobus::to_string(static_cast(inputObjectID))); + CANStackLogger::info("[AUX-N]: Assigned function " + isobus::to_string(static_cast(functionObjectID)) + " to input " + isobus::to_string(static_cast(inputObjectID))); } else { hasError = true; isAlreadyAssigned = true; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Unable to store preferred assignment due to missing auxiliary input device with name: " + isobus::to_string(isoName)); + CANStackLogger::warn("[AUX-N]: Unable to store preferred assignment due to missing auxiliary input device with name: " + isobus::to_string(isoName)); } } else { hasError = true; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Unable to store preferred assignment due to unsupported function type: " + isobus::to_string(functionType)); + CANStackLogger::warn("[AUX-N]: Unable to store preferred assignment due to unsupported function type: " + isobus::to_string(functionType)); } } else { hasError = true; - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Unable to store preferred assignment due to missing auxiliary input device with name: " + isobus::to_string(isoName)); + CANStackLogger::warn("[AUX-N]: Unable to store preferred assignment due to missing auxiliary input device with name: " + isobus::to_string(isoName)); } } parentVT->send_auxiliary_function_assignment_response(functionObjectID, hasError, isAlreadyAssigned); } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Received AuxiliaryAssignmentTypeTwoCommand with wrong data length: " + isobus::to_string(message.get_data_length()) + " but expected 14."); + CANStackLogger::warn("[AUX-N]: Received AuxiliaryAssignmentTypeTwoCommand with wrong data length: " + isobus::to_string(message.get_data_length()) + " but expected 14."); } } break; @@ -2947,7 +2740,7 @@ namespace isobus // bool inputActive = message.get_bool_at(7, 1); // Only in learn mode? // bool controlIsLocked = false; // bool interactionWhileLocked = false; - if (parentVT->get_vt_version_supported(VTVersion::Version6)) + if (parentVT->is_vt_version_supported(VTVersion::Version6)) { // controlIsLocked = message.get_bool_at(7, 2); // interactionWhileLocked = message.get_bool_at(7, 3); @@ -3006,7 +2799,7 @@ namespace isobus else { parentVT->set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Connection Failed Not Enough Memory"); + CANStackLogger::error("[VT]: Connection Failed Not Enough Memory"); } } } @@ -3110,12 +2903,12 @@ namespace isobus { labelMatched = true; parentVT->set_state(StateMachineState::SendLoadVersion); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: VT Server has a matching label for " + isobus::to_string(labelDecoded) + ". It will be loaded and upload will be skipped."); + CANStackLogger::info("[VT]: VT Server has a matching label for " + isobus::to_string(labelDecoded) + ". It will be loaded and upload will be skipped."); break; } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: VT Server has a label for " + isobus::to_string(labelDecoded) + ". This version will be deleted."); + CANStackLogger::info("[VT]: VT Server has a label for " + isobus::to_string(labelDecoded) + ". This version will be deleted."); const std::array deleteBuffer = { static_cast(labelDecoded[0]), static_cast(labelDecoded[1]), @@ -3127,30 +2920,30 @@ namespace isobus }; if (!parentVT->send_delete_version(deleteBuffer)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Failed to send the delete version message for label " + isobus::to_string(labelDecoded)); + CANStackLogger::warn("[VT]: Failed to send the delete version message for label " + isobus::to_string(labelDecoded)); } } } if (!labelMatched) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: No version label from the VT matched. Client will upload the pool and store it instead."); + CANStackLogger::info("[VT]: No version label from the VT matched. Client will upload the pool and store it instead."); parentVT->set_state(StateMachineState::UploadObjectPool); } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Get Versions Response length is not long enough. Message ignored."); + CANStackLogger::warn("[VT]: Get Versions Response length is not long enough. Message ignored."); } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: No version label from the VT matched. Client will upload the pool and store it instead."); + CANStackLogger::info("[VT]: No version label from the VT matched. Client will upload the pool and store it instead."); parentVT->set_state(StateMachineState::UploadObjectPool); } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Get Versions Response ignored!"); + CANStackLogger::warn("[VT]: Get Versions Response ignored!"); } } break; @@ -3161,7 +2954,7 @@ namespace isobus { if (0 == message.get_uint8_at(5)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: Loaded object pool version from VT non-volatile memory with no errors."); + CANStackLogger::info("[VT]: Loaded object pool version from VT non-volatile memory with no errors."); parentVT->set_state(StateMachineState::Connected); //! @todo maybe a better way available than relying on aux function callbacks registered? @@ -3169,11 +2962,11 @@ namespace isobus { if (parentVT->send_auxiliary_functions_preferred_assignment()) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[AUX-N]: Sent preferred assignments after LoadVersionCommand."); + CANStackLogger::debug("[AUX-N]: Sent preferred assignments after LoadVersionCommand."); } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Failed to send preferred assignments after LoadVersionCommand."); + CANStackLogger::warn("[AUX-N]: Failed to send preferred assignments after LoadVersionCommand."); } } } @@ -3182,25 +2975,25 @@ namespace isobus // At least one error is set if (message.get_bool_at(5, 0)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Load Versions Response error: File system error or corruption."); + CANStackLogger::warn("[VT]: Load Versions Response error: File system error or corruption."); } if (message.get_bool_at(5, 1)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Load Versions Response error: Insufficient memory."); + CANStackLogger::warn("[VT]: Load Versions Response error: Insufficient memory."); } if (message.get_bool_at(5, 2)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Load Versions Response error: Any other error."); + CANStackLogger::warn("[VT]: Load Versions Response error: Any other error."); } // Not sure what happened here... should be mostly impossible. Try to upload instead. - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Switching to pool upload instead."); + CANStackLogger::warn("[VT]: Switching to pool upload instead."); parentVT->set_state(StateMachineState::UploadObjectPool); } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Load Versions Response ignored!"); + CANStackLogger::warn("[VT]: Load Versions Response ignored!"); } } break; @@ -3213,28 +3006,28 @@ namespace isobus { // Stored with no error parentVT->set_state(StateMachineState::Connected); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: Stored object pool with no error."); + CANStackLogger::info("[VT]: Stored object pool with no error."); } else { // At least one error is set if (message.get_bool_at(5, 0)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Store Versions Response error: Version label is not correct."); + CANStackLogger::warn("[VT]: Store Versions Response error: Version label is not correct."); } if (message.get_bool_at(5, 1)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Store Versions Response error: Insufficient memory."); + CANStackLogger::warn("[VT]: Store Versions Response error: Insufficient memory."); } if (message.get_bool_at(5, 2)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Store Versions Response error: Any other error."); + CANStackLogger::warn("[VT]: Store Versions Response error: Any other error."); } } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Store Versions Response ignored!"); + CANStackLogger::warn("[VT]: Store Versions Response ignored!"); } } break; @@ -3243,17 +3036,17 @@ namespace isobus { if (0 == message.get_uint8_at(5)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[VT]: Delete Version Response OK!"); + CANStackLogger::info("[VT]: Delete Version Response OK!"); } else { if (message.get_bool_at(5, 1)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Delete Version Response error: Version label is not correct, or unknown."); + CANStackLogger::warn("[VT]: Delete Version Response error: Version label is not correct, or unknown."); } if (message.get_bool_at(5, 3)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Delete Version Response error: Any other error."); + CANStackLogger::warn("[VT]: Delete Version Response error: Any other error."); } } } @@ -3293,30 +3086,101 @@ namespace isobus { if (parentVT->send_auxiliary_functions_preferred_assignment()) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Debug, "[AUX-N]: Sent preferred assignments after EndOfObjectPoolMessage."); + CANStackLogger::debug("[AUX-N]: Sent preferred assignments after EndOfObjectPoolMessage."); } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[AUX-N]: Failed to send preferred assignments after EndOfObjectPoolMessage."); + CANStackLogger::warn("[AUX-N]: Failed to send preferred assignments after EndOfObjectPoolMessage."); } } } else { parentVT->set_state(StateMachineState::Failed); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Error in end of object pool message." + std::string("Faulty Object ") + isobus::to_string(static_cast(objectIDOfFaultyObject)) + std::string(" Faulty Object Parent ") + isobus::to_string(static_cast(parentObjectIDOfFaultyObject)) + std::string(" Pool error bitmask value ") + isobus::to_string(static_cast(objectPoolErrorBitmask))); + CANStackLogger::error("[VT]: Error in end of object pool message." + std::string("Faulty Object ") + isobus::to_string(static_cast(objectIDOfFaultyObject)) + std::string(" Faulty Object Parent ") + isobus::to_string(static_cast(parentObjectIDOfFaultyObject)) + std::string(" Pool error bitmask value ") + isobus::to_string(static_cast(objectPoolErrorBitmask))); if (vtRanOutOfMemory) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Ran out of memory"); + CANStackLogger::error("[VT]: Ran out of memory"); } if (otherErrors) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[VT]: Reported other errors in EOM response"); + CANStackLogger::error("[VT]: Reported other errors in EOM response"); } } } } break; + + case static_cast(Function::HideShowObjectCommand): + case static_cast(Function::EnableDisableObjectCommand): + case static_cast(Function::SelectInputObjectCommand): + case static_cast(Function::ESCCommand): + case static_cast(Function::ControlAudioSignalCommand): + case static_cast(Function::SetAudioVolumeCommand): + case static_cast(Function::ChangeChildLocationCommand): + case static_cast(Function::ChangeChildPositionCommand): + case static_cast(Function::ChangeSizeCommand): + case static_cast(Function::ChangeBackgroundColourCommand): + case static_cast(Function::ChangeNumericValueCommand): + case static_cast(Function::ChangeStringValueCommand): + case static_cast(Function::ChangeEndPointCommand): + case static_cast(Function::ChangeFontAttributesCommand): + case static_cast(Function::ChangeLineAttributesCommand): + case static_cast(Function::ChangeFillAttributesCommand): + case static_cast(Function::ChangeActiveMaskCommand): + case static_cast(Function::ChangeSoftKeyMaskCommand): + case static_cast(Function::ChangeAttributeCommand): + case static_cast(Function::ChangePriorityCommand): + case static_cast(Function::ChangeListItemCommand): + case static_cast(Function::DeleteObjectPoolCommand): + case static_cast(Function::LockUnlockMaskCommand): + case static_cast(Function::ExecuteMacroCommand): + case static_cast(Function::ChangeObjectLabelCommand): + case static_cast(Function::ChangePolygonPointCommand): + case static_cast(Function::ChangePolygonScaleCommand): + case static_cast(Function::GraphicsContextCommand): + case static_cast(Function::GetAttributeValueMessage): + case static_cast(Function::SelectColourMapCommand): + case static_cast(Function::ExecuteExtendedMacroCommand): + case static_cast(Function::SelectActiveWorkingSet): + { + // By checking if it's a response with our control functions, we verify that it's a response to a request we sent. + // This because we only support Working Set Masters at the moment. + if ((parentVT->myControlFunction == message.get_destination_control_function()) && + (parentVT->partnerControlFunction == message.get_source_control_function())) + { + parentVT->commandAwaitingResponse = false; + parentVT->process_command_queue(); + } + } + break; + case static_cast(Function::UnsupportedVTFunctionMessage): + { + std::uint8_t unsupportedFunction = message.get_uint8_at(1); + if (std::find(parentVT->unsupportedFunctions.begin(), parentVT->unsupportedFunctions.end(), unsupportedFunction) == parentVT->unsupportedFunctions.end()) + { + parentVT->unsupportedFunctions.push_back(unsupportedFunction); + } + CANStackLogger::warn("[VT]: Server indicated VT Function '%llu' is unsupported, caching it", unsupportedFunction); + } + break; + default: + { + std::uint8_t unsupportedFunction = message.get_uint8_at(0); + CANStackLogger::warn("[VT]: Server sent function '%llu' which we do not support", unsupportedFunction); + std::array buffer{ + static_cast(Function::UnsupportedVTFunctionMessage), + unsupportedFunction, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + 0xFF, + }; + parentVT->send_message_to_vt(buffer.data(), buffer.size()); + } + break; } } break; @@ -3339,7 +3203,7 @@ namespace isobus { AssignedAuxiliaryInputDevice inputDevice{ message.get_source_control_function()->get_NAME().get_full_name(), modelIdentificationCode, {} }; parentVT->assignedAuxiliaryInputDevices.push_back(inputDevice); - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Info, "[AUX-N]: New auxiliary input device with name: " + isobus::to_string(inputDevice.name) + " and model identification code: " + isobus::to_string(modelIdentificationCode)); + CANStackLogger::info("[AUX-N]: New auxiliary input device with name: " + isobus::to_string(inputDevice.name) + " and model identification code: " + isobus::to_string(modelIdentificationCode)); } } } @@ -3350,14 +3214,14 @@ namespace isobus default: { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: Client unknown message: " + isobus::to_string(static_cast(message.get_identifier().get_parameter_group_number()))); + CANStackLogger::warn("[VT]: Client unknown message: " + isobus::to_string(static_cast(message.get_identifier().get_parameter_group_number()))); } break; } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[VT]: VT-ECU Client message invalid"); + CANStackLogger::warn("[VT]: VT-ECU Client message invalid"); } } @@ -4572,6 +4436,118 @@ namespace isobus return retVal; } + bool VirtualTerminalClient::is_function_unsupported(std::uint8_t functionCode) const + { + return std::find(unsupportedFunctions.begin(), unsupportedFunctions.end(), functionCode) != unsupportedFunctions.end(); + } + + bool VirtualTerminalClient::is_function_unsupported(Function function) const + { + return is_function_unsupported(static_cast(function)); + } + + bool VirtualTerminalClient::send_command(const std::vector &data) + { + if (commandAwaitingResponse) + { + if (SystemTiming::time_expired_ms(lastCommandTimestamp_ms, 1500)) + { + CANStackLogger::warn("[VT]: Server response to a command timed out"); + commandAwaitingResponse = false; + } + else + { + // We're still waiting for a response to the last command, so we can't send another one yet + return false; + } + } + + if (!get_is_connected()) + { + CANStackLogger::warn("[VT]: Cannot send command, not connected"); + return false; + } + + bool success = send_message_to_vt(data.data(), data.size()); + + if (success) + { + commandAwaitingResponse = true; + lastCommandTimestamp_ms = SystemTiming::get_timestamp_ms(); + } + return success; + } + + bool VirtualTerminalClient::queue_command(const std::vector &data, bool replace) + { + std::uint8_t functionCode = data[0]; + if (is_function_unsupported(functionCode)) + { + return false; + } + + if (get_is_connected() && send_command(data)) + { + return true; + } + + if (replace && replace_command(data)) + { + return true; + } + +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + std::lock_guard lock(commandQueueMutex); +#endif + commandQueue.emplace_back(data); + return true; + } + + bool VirtualTerminalClient::replace_command(const std::vector &data) + { + bool alreadyReplaced = false; + for (auto it = commandQueue.begin(); it != commandQueue.end();) + { + bool matchesFunctionCode = (it->at(0) == data[0]); + if (matchesFunctionCode) + { + if (!alreadyReplaced) + { + *it = data; + alreadyReplaced = true; + it++; + } + else + { + it = commandQueue.erase(it); + } + } + } + return alreadyReplaced; + } + + void VirtualTerminalClient::process_command_queue() + { + if (!get_is_connected()) + { + return; + } +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + std::lock_guard lock(commandQueueMutex); +#endif + for (auto it = commandQueue.begin(); it != commandQueue.end();) + { + if (send_command(*it)) + { + it = commandQueue.erase(it); + } + else + { + it++; + } + } + } + void VirtualTerminalClient::worker_thread_function() { #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO diff --git a/src/isobus_virtual_terminal_client.hpp b/src/isobus_virtual_terminal_client.hpp index 247740d..b32c553 100644 --- a/src/isobus_virtual_terminal_client.hpp +++ b/src/isobus_virtual_terminal_client.hpp @@ -23,6 +23,7 @@ #include #if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO +#include #include #endif @@ -42,6 +43,84 @@ namespace isobus class VirtualTerminalClient { public: + /// @brief Enumerates the multiplexor byte values for VT commands + enum class Function : std::uint8_t + { + SoftKeyActivationMessage = 0x00, + ButtonActivationMessage = 0x01, + PointingEventMessage = 0x02, + VTSelectInputObjectMessage = 0x03, + VTESCMessage = 0x04, + VTChangeNumericValueMessage = 0x05, + VTChangeActiveMaskMessage = 0x06, + VTChangeSoftKeyMaskMessage = 0x07, + VTChangeStringValueMessage = 0x08, + VTOnUserLayoutHideShowMessage = 0x09, + VTControlAudioSignalTerminationMessage = 0x0A, + ObjectPoolTransferMessage = 0x11, + EndOfObjectPoolMessage = 0x12, + AuxiliaryAssignmentTypeOneCommand = 0x20, + AuxiliaryInputTypeOneStatus = 0x21, + PreferredAssignmentCommand = 0x22, + AuxiliaryInputTypeTwoMaintenanceMessage = 0x23, + AuxiliaryAssignmentTypeTwoCommand = 0x24, + AuxiliaryInputStatusTypeTwoEnableCommand = 0x25, + AuxiliaryInputTypeTwoStatusMessage = 0x26, + AuxiliaryCapabilitiesRequest = 0x27, + SelectActiveWorkingSet = 0x90, + ESCCommand = 0x92, + HideShowObjectCommand = 0xA0, + EnableDisableObjectCommand = 0xA1, + SelectInputObjectCommand = 0xA2, + ControlAudioSignalCommand = 0xA3, + SetAudioVolumeCommand = 0xA4, + ChangeChildLocationCommand = 0xA5, + ChangeSizeCommand = 0xA6, + ChangeBackgroundColourCommand = 0xA7, + ChangeNumericValueCommand = 0xA8, + ChangeEndPointCommand = 0xA9, + ChangeFontAttributesCommand = 0xAA, + ChangeLineAttributesCommand = 0xAB, + ChangeFillAttributesCommand = 0xAC, + ChangeActiveMaskCommand = 0xAD, + ChangeSoftKeyMaskCommand = 0xAE, + ChangeAttributeCommand = 0xAF, + ChangePriorityCommand = 0xB0, + ChangeListItemCommand = 0xB1, + DeleteObjectPoolCommand = 0xB2, + ChangeStringValueCommand = 0xB3, + ChangeChildPositionCommand = 0xB4, + ChangeObjectLabelCommand = 0xB5, + ChangePolygonPointCommand = 0xB6, + ChangePolygonScaleCommand = 0xB7, + GraphicsContextCommand = 0xB8, + GetAttributeValueMessage = 0xB9, + SelectColourMapCommand = 0xBA, + IdentifyVTMessage = 0xBB, + ExecuteExtendedMacroCommand = 0xBC, + LockUnlockMaskCommand = 0xBD, + ExecuteMacroCommand = 0xBE, + GetMemoryMessage = 0xC0, + GetSupportedWidecharsMessage = 0xC1, + GetNumberOfSoftKeysMessage = 0xC2, + GetTextFontDataMessage = 0xC3, + GetWindowMaskDataMessage = 0xC4, + GetSupportedObjectsMessage = 0xC5, + GetHardwareMessage = 0xC7, + StoreVersionCommand = 0xD0, + LoadVersionCommand = 0xD1, + DeleteVersionCommand = 0xD2, + ExtendedGetVersionsMessage = 0xD3, + ExtendedStoreVersionCommand = 0xD4, + ExtendedLoadVersionCommand = 0xD5, + ExtendedDeleteVersionCommand = 0xD6, + GetVersionsMessage = 0xDF, + GetVersionsResponse = 0xE0, + UnsupportedVTFunctionMessage = 0xFD, + VTStatusMessage = 0xFE, + WorkingSetMaintenanceMessage = 0xFF + }; + /// @brief Enumerates the states that can be sent with a hide/show object command enum class HideShowObjectCommand : std::uint8_t { @@ -285,6 +364,7 @@ namespace isobus /// @brief Allows easy comparison of two `AssignedAuxiliaryFunction` objects /// @param[in] other the object to compare against + /// @returns true if the objects are equal, false otherwise bool operator==(const AssignedAuxiliaryFunction &other) const; std::uint16_t functionObjectID; ///< The object ID of the function present in our object pool @@ -292,8 +372,6 @@ namespace isobus AuxiliaryTypeTwoFunctionType functionType; ///< The type of function }; - static constexpr std::uint16_t NULL_OBJECT_ID = 0xFFFF; ///< The NULL Object ID, usually drawn as blank space - /// @brief The constructor for a VirtualTerminalClient /// @param[in] partner The VT server control function /// @param[in] clientSource The internal control function to communicate from @@ -439,68 +517,56 @@ namespace isobus std::uint16_t value2; ///< The second value }; - /// @brief Add a listener for when a soft key is pressed or released - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_soft_key_event_listener(std::function callback); - - /// @brief Add a listener for when a button is pressed or released - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_button_event_listener(std::function callback); - - /// @brief Add a listener for when a pointing event is "pressed or released" - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_pointing_event_listener(std::function callback); - - /// @brief Add a listener for when an input object event is triggered - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_select_input_object_event_listener(std::function callback); - - /// @brief Add a listener for when an ESC message is received, e.g. an open object input is closed - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_esc_message_event_listener(std::function callback); - - /// @brief Add a listener for when a numeric value is changed in an input object - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_change_numeric_value_event_listener(std::function callback); - - /// @brief Add a listener for when the active mask is changed + /// @brief The event dispatcher for when a soft key is pressed or released + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_soft_key_event_dispatcher(); + + /// @brief The event dispatcher for when a button is pressed or released + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_button_event_dispatcher(); + + /// @brief The event dispatcher for when a pointing event is "pressed or released" + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_pointing_event_dispatcher(); + + /// @brief The event dispatcher for when an input object event is triggered + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_select_input_object_event_dispatcher(); + + /// @brief The event dispatcher for when an ESC message is received, e.g. an open object input is closed + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_esc_message_event_dispatcher(); + + /// @brief The event dispatcher for when a numeric value is changed in an input object + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_change_numeric_value_event_dispatcher(); + + /// @brief The event dispatcher for when the active mask is changed /// @details The VT sends this whenever there are missing object references or errors in the mask. - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_change_active_mask_event_listener(std::function callback); + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_change_active_mask_event_dispatcher(); - /// @brief Add a listener for when the soft key mask is changed + /// @brief The event dispatcher for when the soft key mask is changed /// @details The VT sends this whenever there are missing object references or errors in the mask. - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_change_soft_key_mask_event_listener(std::function callback); + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_change_soft_key_mask_event_dispatcher(); - /// @brief Add a listener for when a string value is changed + /// @brief The event dispatcher for when a string value is changed /// @details The object could be either the input string object or the referenced string variable object. - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_change_string_value_event_listener(std::function callback); + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_change_string_value_event_dispatcher(); - /// @brief Add a listener for when a user-layout object is hidden or shown - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_user_layout_hide_show_event_listener(std::function callback); + /// @brief The event dispatcher for when a user-layout object is hidden or shown + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_user_layout_hide_show_event_dispatcher(); - /// @brief Add a listener for when an audio signal is terminated - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_vt_control_audio_signal_termination_event_listener(std::function callback); + /// @brief The event dispatcher for when an audio signal is terminated + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_vt_control_audio_signal_termination_event_dispatcher(); - /// @brief Add a listener for for when a change in auxiliary input for a function is received - /// @param[in] callback The callback to be invoked - /// @returns A shared pointer to the callback, which must be kept alive for as long as the callback is needed - std::shared_ptr add_auxiliary_function_event_listener(std::function callback); + /// @brief The event dispatcher for for when a change in auxiliary input for a function is received + /// @returns A reference to the event dispatcher, used to add listeners + EventDispatcher &get_auxiliary_function_event_dispatcher(); /// @brief Set the model identification code of our auxiliary input device. /// @details The model identification code is used to allow other devices identify @@ -532,6 +598,7 @@ namespace isobus void update_auxiliary_input(const std::uint16_t auxiliaryInputID, const std::uint16_t value1, const std::uint16_t value2, const bool controlLocked = false); // Command Messages + /// @brief Sends a hide/show object command /// @details This command is used to hide or show a Container object. /// This pertains to the visibility of the object as well as its @@ -539,8 +606,8 @@ namespace isobus /// objects, the VT generates an error in the response. /// @param[in] objectID The ID of the target object /// @param[in] command The target hide/show state of the object - /// @returns true if the message was sent successfully - bool send_hide_show_object(std::uint16_t objectID, HideShowObjectCommand command) const; + /// @returns true if the message is being sent successfully + bool send_hide_show_object(std::uint16_t objectID, HideShowObjectCommand command); /// @brief Sends an enable/disable object command /// @details This command is used to enable or disable an input field object @@ -549,19 +616,19 @@ namespace isobus /// It is allowed to enable already enabled objects and to disable already disabled objects. /// @param[in] objectID The ID of the target object /// @param[in] command The target enable/disable state of the object - /// @returns true if the message was sent successfully - bool send_enable_disable_object(std::uint16_t objectID, EnableDisableObjectCommand command) const; + /// @returns true if the message is being sent successfully + bool send_enable_disable_object(std::uint16_t objectID, EnableDisableObjectCommand command); /// @brief Sends a select input object command /// @details This command is used to force the selection of an input field, Button, or Key object. /// @param[in] objectID The ID of the target object /// @param[in] option The method by which the object will be selected - /// @returns true if the message was sent successfully - bool send_select_input_object(std::uint16_t objectID, SelectInputObjectOptions option) const; + /// @returns true if the message is being sent successfully + bool send_select_input_object(std::uint16_t objectID, SelectInputObjectOptions option); /// @brief Sends the ESC message (Escape) - /// @returns true if the message was sent successfully - bool send_ESC() const; + /// @returns true if the message is being sent successfully + bool send_ESC(); /// @brief Sends the control audio signal command /// @details This command may be used to control the audio on the VT. @@ -571,8 +638,8 @@ namespace isobus /// @param[in] frequency_hz The audio frequency to command in Hz /// @param[in] duration_ms Duration of the signal activation /// @param[in] offTimeDuration_ms The amount of silent time in the signal - /// @returns true if the message was sent successfully - bool send_control_audio_signal(std::uint8_t activations, std::uint16_t frequency_hz, std::uint16_t duration_ms, std::uint16_t offTimeDuration_ms) const; + /// @returns true if the message is being sent successfully + bool send_control_audio_signal(std::uint8_t activations, std::uint16_t frequency_hz, std::uint16_t duration_ms, std::uint16_t offTimeDuration_ms); /// @brief Sends the set audio volume command /// @details This command applies to subsequent Control Audio Signal commands. @@ -580,8 +647,8 @@ namespace isobus /// the Audio device is busy bit in the response.This command should not affect in any way /// the volume settings of other Working Sets and shall not affect the volume of Alarm Masks. /// @param[in] volume_percent The volume percentage to set the VT server to - /// @returns true if the message was sent successfully - bool send_set_audio_volume(std::uint8_t volume_percent) const; + /// @returns true if the message is being sent successfully + bool send_set_audio_volume(std::uint8_t volume_percent); /// @brief Sends the change child location command /// @details The Change Child Location command is used to change the position of an object. The new position is set @@ -596,8 +663,8 @@ namespace isobus /// @param[in] parentObjectID The ID of the object's parent object /// @param[in] relativeXPositionChange The amount to change the X position by (px) /// @param[in] relativeYPositionChange The amount to change the Y position by (px) - /// @returns true if the message was sent successfully - bool send_change_child_location(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint8_t relativeXPositionChange, std::uint8_t relativeYPositionChange) const; + /// @returns true if the message is being sent successfully + bool send_change_child_location(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint8_t relativeXPositionChange, std::uint8_t relativeYPositionChange); /// @brief Sends the change child position command /// @details The new position is set relative to the parent object's position. @@ -614,8 +681,8 @@ namespace isobus /// @param[in] parentObjectID The ID of the object's parent object /// @param[in] xPosition The new X position of the object (px) /// @param[in] yPosition The new Y position of the object (px) - /// @returns true if the message was sent successfully - bool send_change_child_position(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint16_t xPosition, std::uint16_t yPosition) const; + /// @returns true if the message is being sent successfully + bool send_change_child_position(std::uint16_t objectID, std::uint16_t parentObjectID, std::uint16_t xPosition, std::uint16_t yPosition); /// @brief Sends the change size command /// @details A value of 0 for width or height or both @@ -623,22 +690,22 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] newWidth The new width of the object /// @param[in] newHeight The new height of the object - /// @returns true if the message was sent successfully - bool send_change_size_command(std::uint16_t objectID, std::uint16_t newWidth, std::uint16_t newHeight) const; + /// @returns true if the message is being sent successfully + bool send_change_size_command(std::uint16_t objectID, std::uint16_t newWidth, std::uint16_t newHeight); /// @brief Sends the change background colour command /// @param[in] objectID The ID of the target object /// @param[in] colour The new background colour of the object - /// @returns true if the message was sent successfully - bool send_change_background_colour(std::uint16_t objectID, std::uint8_t colour) const; + /// @returns true if the message is being sent successfully + bool send_change_background_colour(std::uint16_t objectID, std::uint8_t colour); /// @brief Sends the change numeric value command /// @details The size of the object shall not be changed by this command. Only the object indicated in the /// command is to be changed, variables referenced by the object are not changed. /// @param[in] objectID The ID of the target object /// @param[in] value The new numeric value of the object - /// @returns true if the message was sent successfully - bool send_change_numeric_value(std::uint16_t objectID, std::uint32_t value) const; + /// @returns true if the message is being sent successfully + bool send_change_numeric_value(std::uint16_t objectID, std::uint32_t value); /// @brief Sends the change string value command /// @details The size of the object shall not be changed by this command. Only the object indicated in the @@ -648,8 +715,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] stringLength The length of the string to be sent /// @param[in] value The string to be sent - /// @returns true if the message was sent successfully - bool send_change_string_value(std::uint16_t objectID, uint16_t stringLength, const char *value) const; + /// @returns true if the message is being sent successfully + bool send_change_string_value(std::uint16_t objectID, uint16_t stringLength, const char *value); /// @brief Sends the change string value command (with a c++ string instead of buffer + length) /// @details The size of the object shall not be changed by this command. Only the object indicated in the @@ -658,16 +725,16 @@ namespace isobus /// this case the VT shall pad the value attribute with space characters. /// @param[in] objectID The ID of the target object /// @param[in] value The string to be sent - /// @returns true if the message was sent successfully - bool send_change_string_value(std::uint16_t objectID, const std::string &value) const; + /// @returns true if the message is being sent successfully + bool send_change_string_value(std::uint16_t objectID, const std::string &value); /// @brief Sends the change endpoint command, which changes the end of an output line /// @param[in] objectID The ID of the target object /// @param[in] width_px The width to change the output line to /// @param[in] height_px The height to change the output line to /// @param[in] direction The line direction (refer to output line object attributes) - /// @returns true if the message was sent successfully - bool send_change_endpoint(std::uint16_t objectID, std::uint16_t width_px, std::uint16_t height_px, LineDirection direction) const; + /// @returns true if the message is being sent successfully + bool send_change_endpoint(std::uint16_t objectID, std::uint16_t width_px, std::uint16_t height_px, LineDirection direction); /// @brief Sends the change font attributes command /// @details This command is used to change the Font Attributes in a Font Attributes object. @@ -676,8 +743,8 @@ namespace isobus /// @param[in] size Font size /// @param[in] type Font Type /// @param[in] styleBitfield The font style encoded as a bitfield - /// @returns true if the message was sent successfully - bool send_change_font_attributes(std::uint16_t objectID, std::uint8_t colour, FontSize size, std::uint8_t type, std::uint8_t styleBitfield) const; + /// @returns true if the message is being sent successfully + bool send_change_font_attributes(std::uint16_t objectID, std::uint8_t colour, FontSize size, std::uint8_t type, std::uint8_t styleBitfield); /// @brief Sends the change line attributes command /// @details This command is used to change the Line Attributes in a Line Attributes object. @@ -685,8 +752,8 @@ namespace isobus /// @param[in] colour See the standard VT colour palette for more details /// @param[in] width The line width /// @param[in] lineArtBitmask The line art, encoded as a bitfield (See ISO11783-6 for details) - /// @returns true if the message was sent successfully - bool send_change_line_attributes(std::uint16_t objectID, std::uint8_t colour, std::uint8_t width, std::uint16_t lineArtBitmask) const; + /// @returns true if the message is being sent successfully + bool send_change_line_attributes(std::uint16_t objectID, std::uint8_t colour, std::uint8_t width, std::uint16_t lineArtBitmask); /// @brief Sends the change fill attributes command /// @details This command is used to change the Fill Attributes in a Fill Attributes object. @@ -694,16 +761,16 @@ namespace isobus /// @param[in] fillType The fill type /// @param[in] colour See the standard VT colour palette for more details /// @param[in] fillPatternObjectID Object ID to a fill pattern or NULL_OBJECT_ID - /// @returns true if the message was sent successfully - bool send_change_fill_attributes(std::uint16_t objectID, FillType fillType, std::uint8_t colour, std::uint16_t fillPatternObjectID) const; + /// @returns true if the message is being sent successfully + bool send_change_fill_attributes(std::uint16_t objectID, FillType fillType, std::uint8_t colour, std::uint16_t fillPatternObjectID); /// @brief Sends the change active mask command /// @details This command is used to change the active mask of a Working Set /// to either a Data Mask object or an Alarm Mask object. /// @param[in] workingSetObjectID The ID of the working set /// @param[in] newActiveMaskObjectID The object ID of the new active mask - /// @returns true if the message was sent successfully - bool send_change_active_mask(std::uint16_t workingSetObjectID, std::uint16_t newActiveMaskObjectID) const; + /// @returns true if the message is being sent successfully + bool send_change_active_mask(std::uint16_t workingSetObjectID, std::uint16_t newActiveMaskObjectID); /// @brief Sends the change softkey mask command /// @details This command is used to change the Soft Key Mask associated with a @@ -711,8 +778,8 @@ namespace isobus /// @param[in] type The mask type, alarm or data /// @param[in] dataOrAlarmMaskObjectID The object ID of the target mask /// @param[in] newSoftKeyMaskObjectID The object ID of the new softkey mask - /// @returns true if the message was sent successfully - bool send_change_softkey_mask(MaskType type, std::uint16_t dataOrAlarmMaskObjectID, std::uint16_t newSoftKeyMaskObjectID) const; + /// @returns true if the message is being sent successfully + bool send_change_softkey_mask(MaskType type, std::uint16_t dataOrAlarmMaskObjectID, std::uint16_t newSoftKeyMaskObjectID); /// @brief Sends the change attribute command /// @details This command is used to change any attribute with an assigned Attribute ID. @@ -720,8 +787,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] attributeID The attribute ID of the attribute being changed /// @param[in] value The new attribute value - /// @returns true if the message was sent successfully - bool send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, std::uint32_t value) const; + /// @returns true if the message is being sent successfully + bool send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, std::uint32_t value); /// @brief Sends the change attribute command (for float values) /// @details This command is used to change a float attribute with an assigned Attribute ID. @@ -729,8 +796,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] attributeID The attribute ID of the attribute being changed /// @param[in] value The new attribute value - /// @returns true if the message was sent successfully - bool send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, float value) const; + /// @returns true if the message is being sent successfully + bool send_change_attribute(std::uint16_t objectID, std::uint8_t attributeID, float value); /// @brief Sends the change priority command /// @details This command is used to change the priority of an Alarm Mask. @@ -740,8 +807,8 @@ namespace isobus /// or should no longer be the active Working Set and mask. /// @param[in] alarmMaskObjectID The object ID of the target alarm mask /// @param[in] priority The new priority for the mask - /// @returns true if the message was sent successfully - bool send_change_priority(std::uint16_t alarmMaskObjectID, AlarmMaskPriority priority) const; + /// @returns true if the message is being sent successfully + bool send_change_priority(std::uint16_t alarmMaskObjectID, AlarmMaskPriority priority); /// @brief Sends the change list item command /// @details This command is used to change a list item in an Input List object, @@ -751,8 +818,8 @@ namespace isobus /// @param[in] objectID The object ID of the list /// @param[in] listIndex The index in the list to edit /// @param[in] newObjectID The new object ID for the specified list index, or NULL_OBJECT_ID. - /// @returns true if the message was sent successfully - bool send_change_list_item(std::uint16_t objectID, std::uint8_t listIndex, std::uint16_t newObjectID) const; + /// @returns true if the message is being sent successfully + bool send_change_list_item(std::uint16_t objectID, std::uint8_t listIndex, std::uint16_t newObjectID); /// @brief Sends the lock unlock mask command /// @details This command is used by a Working Set to disallow or allow @@ -764,14 +831,14 @@ namespace isobus /// @param[in] state The target lock/unlock state /// @param[in] objectID The object ID of the target mask /// @param[in] timeout_ms The max time to lock the mask, or 0 for no timeout. Does not apply to unlock commands. - /// @returns true if the message was sent successfully - bool send_lock_unlock_mask(MaskLockState state, std::uint16_t objectID, std::uint16_t timeout_ms) const; + /// @returns true if the message is being sent successfully + bool send_lock_unlock_mask(MaskLockState state, std::uint16_t objectID, std::uint16_t timeout_ms); /// @brief Sends the execute macro command /// @details This command is used to execute a Macro. /// @param[in] objectID The ID of the target object - /// @returns true if the message was sent successfully - bool send_execute_macro(std::uint16_t objectID) const; + /// @returns true if the message is being sent successfully + bool send_execute_macro(std::uint16_t objectID); /// @brief Sends the change object label command /// @details This command is used by an ECU to change a label of an object. @@ -779,8 +846,8 @@ namespace isobus /// @param[in] labelStringObjectID The label's object ID /// @param[in] fontType The font type or NULL_OBJECT_ID /// @param[in] graphicalDesignatorObjectID Object ID of an object to be used as a graphic representation of the object label or NULL_OBJECT_ID - /// @returns true if the message was sent successfully - bool send_change_object_label(std::uint16_t objectID, std::uint16_t labelStringObjectID, std::uint8_t fontType, std::uint16_t graphicalDesignatorObjectID) const; + /// @returns true if the message is being sent successfully + bool send_change_object_label(std::uint16_t objectID, std::uint16_t labelStringObjectID, std::uint8_t fontType, std::uint16_t graphicalDesignatorObjectID); /// @brief Sends change polygon point command /// @details This command is used by a Working Set to modify a point in an Output Polygon object. @@ -788,8 +855,8 @@ namespace isobus /// @param[in] pointIndex The index of the point in the polygon to edit /// @param[in] newXValue The new X axis value (px) /// @param[in] newYValue The new Y axis value (px) - /// @returns true if the message was sent successfully - bool send_change_polygon_point(std::uint16_t objectID, std::uint8_t pointIndex, std::uint16_t newXValue, std::uint16_t newYValue) const; + /// @returns true if the message is being sent successfully + bool send_change_polygon_point(std::uint16_t objectID, std::uint8_t pointIndex, std::uint16_t newXValue, std::uint16_t newYValue); /// @brief Sends the change polygon scale command /// @details This command is used by a Working Set to change the scale of a complete Output Polygon object. This @@ -797,24 +864,24 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] widthAttribute New width attribute /// @param[in] heightAttribute New height attribute - /// @returns true if the message was sent successfully - bool send_change_polygon_scale(std::uint16_t objectID, std::uint16_t widthAttribute, std::uint16_t heightAttribute) const; + /// @returns true if the message is being sent successfully + bool send_change_polygon_scale(std::uint16_t objectID, std::uint16_t widthAttribute, std::uint16_t heightAttribute); /// @brief Sends the select colour map or palette command /// @param[in] objectID The object to select - /// @returns true if the message was sent successfully - bool send_select_colour_map_or_palette(std::uint16_t objectID) const; + /// @returns true if the message is being sent successfully + bool send_select_colour_map_or_palette(std::uint16_t objectID); /// @brief Sends the execute extended macro command /// @details Executes an extended macro /// @param[in] objectID The object ID of the extended macro to execute - /// @returns true if the message was sent successfully - bool send_execute_extended_macro(std::uint16_t objectID) const; + /// @returns true if the message is being sent successfully + bool send_execute_extended_macro(std::uint16_t objectID); /// @brief Sends the select active working set command /// @param[in] NAMEofWorkingSetMasterForDesiredWorkingSet The NAME of the target working set master - /// @returns true if the message was sent successfully - bool send_select_active_working_set(std::uint64_t NAMEofWorkingSetMasterForDesiredWorkingSet) const; + /// @returns true if the message is being sent successfully + bool send_select_active_working_set(std::uint64_t NAMEofWorkingSetMasterForDesiredWorkingSet); // Graphics Context Commands: /// @brief Sends the set graphics cursor command @@ -822,8 +889,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] xPosition The new X position (px) /// @param[in] yPosition The new Y position (px) - /// @returns true if the message was sent successfully - bool send_set_graphics_cursor(std::uint16_t objectID, std::int16_t xPosition, std::int16_t yPosition) const; + /// @returns true if the message is being sent successfully + bool send_set_graphics_cursor(std::uint16_t objectID, std::int16_t xPosition, std::int16_t yPosition); /// @brief Sends the move graphics cursor command /// @details This command alters the graphics cursor x/y attributes of the object @@ -832,23 +899,23 @@ namespace isobus /// @param[in] xOffset The new relative X offset of the cursor /// @param[in] yOffset The new relative Y offset of the cursor /// @returns true if the message was sent successfully - bool send_move_graphics_cursor(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const; + bool send_move_graphics_cursor(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset); /// @brief Sends the set foreground colour command /// @details This command modifies the foreground colour /// attribute.The graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] colour See standard colour palette, 0-255 - /// @returns true if the message was sent successfully - bool send_set_foreground_colour(std::uint16_t objectID, std::uint8_t colour) const; + /// @returns true if the message is being sent successfully + bool send_set_foreground_colour(std::uint16_t objectID, std::uint8_t colour); /// @brief Sends the set background colour command /// @details This command modifies the background colour /// attribute.The graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] colour See standard colour palette, 0-255 - /// @returns true if the message was sent successfully - bool send_set_background_colour(std::uint16_t objectID, std::uint8_t colour) const; + /// @returns true if the message is being sent successfully + bool send_set_background_colour(std::uint16_t objectID, std::uint8_t colour); /// @brief Sends the set line attributes object id /// @details This command modifies the Output Line object @@ -857,8 +924,8 @@ namespace isobus /// The graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] lineAttributeobjectID The object ID of the line attribute - /// @returns true if the message was sent successfully - bool send_set_line_attributes_object_id(std::uint16_t objectID, std::uint16_t lineAttributeobjectID) const; + /// @returns true if the message is being sent successfully + bool send_set_line_attributes_object_id(std::uint16_t objectID, std::uint16_t lineAttributeobjectID); /// @brief Sends the fill attributes object id /// @details This command modifies the fill object attribute. All @@ -867,8 +934,8 @@ namespace isobus /// graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] fillAttributeobjectID The object ID of the fill attribute - /// @returns true if the message was sent successfully - bool send_set_fill_attributes_object_id(std::uint16_t objectID, std::uint16_t fillAttributeobjectID) const; + /// @returns true if the message is being sent successfully + bool send_set_fill_attributes_object_id(std::uint16_t objectID, std::uint16_t fillAttributeobjectID); /// @brief Sends the set fill attributes object ID command /// @details This command modifies the font object attribute. All @@ -877,8 +944,8 @@ namespace isobus /// The graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] fontAttributesObjectID The object ID of the font attribute - /// @returns true if the message was sent successfully - bool send_set_font_attributes_object_id(std::uint16_t objectID, std::uint16_t fontAttributesObjectID) const; + /// @returns true if the message is being sent successfully + bool send_set_font_attributes_object_id(std::uint16_t objectID, std::uint16_t fontAttributesObjectID); /// @brief Sends the erase rectangle command /// @details Fills the rectangle at the graphics cursor using the @@ -888,8 +955,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] width The width of the rectangle /// @param[in] height The height of the rectangle - /// @returns true if the message was sent successfully - bool send_erase_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const; + /// @returns true if the message is being sent successfully + bool send_erase_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height); /// @brief Sends the draw point command /// @details Sets the pixel to the foreground colour. The graphics @@ -897,8 +964,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] xOffset The pixel X offset relative to the cursor /// @param[in] yOffset The pixel Y offset relative to the cursor - /// @returns true if the message was sent successfully - bool send_draw_point(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const; + /// @returns true if the message is being sent successfully + bool send_draw_point(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset); /// @brief Sends the draw line command /// @details Draws a line from the graphics cursor to the specified @@ -909,8 +976,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] xOffset The pixel X offset relative to the cursor /// @param[in] yOffset The pixel Y offset relative to the cursor - /// @returns true if the message was sent successfully - bool send_draw_line(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset) const; + /// @returns true if the message is being sent successfully + bool send_draw_line(std::uint16_t objectID, std::int16_t xOffset, std::int16_t yOffset); /// @brief Sends the draw rectangle command /// @details Draws a rectangle at the graphics cursor. The @@ -922,8 +989,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] width The width of the rectangle (px) /// @param[in] height The height of the rectangle (px) - /// @returns true if the message was sent successfully - bool send_draw_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const; + /// @returns true if the message is being sent successfully + bool send_draw_rectangle(std::uint16_t objectID, std::uint16_t width, std::uint16_t height); /// @brief Sends the draw closed ellipse message /// @details Draws a closed ellipse bounded by the rectangle @@ -936,8 +1003,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] width The width of the ellipse (px) /// @param[in] height The height of the ellipse (px) - /// @returns true if the message was sent successfully - bool send_draw_closed_ellipse(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const; + /// @returns true if the message is being sent successfully + bool send_draw_closed_ellipse(std::uint16_t objectID, std::uint16_t width, std::uint16_t height); /// @brief Sends the draw polygon command /// @details Draws a polygon from the graphics cursor to the first @@ -957,8 +1024,8 @@ namespace isobus /// @param[in] numberOfPoints Number of points in the polygon /// @param[in] listOfXOffsetsRelativeToCursor A list of X offsets for the points, relative to the cursor /// @param[in] listOfYOffsetsRelativeToCursor A list of Y offsets for the points, relative to the cursor - /// @returns true if the message was sent successfully - bool send_draw_polygon(std::uint16_t objectID, std::uint8_t numberOfPoints, std::int16_t *listOfXOffsetsRelativeToCursor, std::int16_t *listOfYOffsetsRelativeToCursor) const; + /// @returns true if the message is being sent successfully + bool send_draw_polygon(std::uint16_t objectID, std::uint8_t numberOfPoints, const std::int16_t *listOfXOffsetsRelativeToCursor, const std::int16_t *listOfYOffsetsRelativeToCursor); /// @brief Sends the draw text command /// @details Draws the given text using the Font Attributes object. @@ -970,8 +1037,8 @@ namespace isobus /// @param[in] transparent Denotes if the text background is transparent /// @param[in] textLength String length /// @param[in] value A buffer to the text to draw with length `textLength` - /// @returns true if the message was sent successfully - bool send_draw_text(std::uint16_t objectID, bool transparent, std::uint8_t textLength, const char *value) const; + /// @returns true if the message is being sent successfully + bool send_draw_text(std::uint16_t objectID, bool transparent, std::uint8_t textLength, const char *value); /// @brief Sends the pan viewport command /// @details This command modifies the viewport X and Y @@ -981,8 +1048,8 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] xAttribute The viewport X attribute /// @param[in] yAttribute The viewport Y attribute - /// @returns true if the message was sent successfully - bool send_pan_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute) const; + /// @returns true if the message is being sent successfully + bool send_pan_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute); /// @brief Sends the zoom viewport command /// @details This command allows magnification of the viewport @@ -990,8 +1057,8 @@ namespace isobus /// zoom value. The graphics cursor is not moved. /// @param[in] objectID The ID of the target object /// @param[in] zoom Zoom value, -32.0 to 32.0 - /// @returns true if the message was sent successfully - bool send_zoom_viewport(std::uint16_t objectID, float zoom) const; + /// @returns true if the message is being sent successfully + bool send_zoom_viewport(std::uint16_t objectID, float zoom); /// @brief Sends the pan and zoom viewport command /// @details This command allows both panning and zooming at the same time. @@ -999,8 +1066,8 @@ namespace isobus /// @param[in] xAttribute The viewport X attribute /// @param[in] yAttribute The viewport Y attribute /// @param[in] zoom Zoom value, -32.0 to 32.0 - /// @returns true if the message was sent successfully - bool send_pan_and_zoom_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute, float zoom) const; + /// @returns true if the message is being sent successfully + bool send_pan_and_zoom_viewport(std::uint16_t objectID, std::int16_t xAttribute, std::int16_t yAttribute, float zoom); /// @brief Sends the change viewport size command /// @details This command changes the size of the viewport and @@ -1009,39 +1076,39 @@ namespace isobus /// @param[in] objectID The ID of the target object /// @param[in] width The width of the viewport /// @param[in] height The height of the viewport - /// @returns true if the message was sent successfully - bool send_change_viewport_size(std::uint16_t objectID, std::uint16_t width, std::uint16_t height) const; + /// @returns true if the message is being sent successfully + bool send_change_viewport_size(std::uint16_t objectID, std::uint16_t width, std::uint16_t height); /// @brief Sends the draw VT object command /// @details his command draws the VT Object specified by the Object ID /// at the current graphics cursor location. /// @param[in] graphicsContextObjectID The ID of the target graphics context object /// @param[in] VTObjectID The object ID to draw - /// @returns true if the message was sent successfully - bool send_draw_vt_object(std::uint16_t graphicsContextObjectID, std::uint16_t VTObjectID) const; + /// @returns true if the message is being sent successfully + bool send_draw_vt_object(std::uint16_t graphicsContextObjectID, std::uint16_t VTObjectID); /// @brief Sends the copy canvas to picture graphic command /// @details This command copies the current canvas of the /// Graphics Context Object into the Picture Graphic object specified. /// @param[in] graphicsContextObjectID The ID of the target graphics context object /// @param[in] objectID The picture graphic's object ID to copy to - /// @returns true if the message was sent successfully - bool send_copy_canvas_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) const; + /// @returns true if the message is being sent successfully + bool send_copy_canvas_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID); /// @brief Sends the copy viewport to picture graphic command /// @details This command copies the current Viewport of the GCO into the /// specified picture graphic. /// @param[in] graphicsContextObjectID The ID of the target graphics context object /// @param[in] objectID The picture graphic's object ID to copy to - /// @returns true if the message was sent successfully - bool send_copy_viewport_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID) const; + /// @returns true if the message is being sent successfully + bool send_copy_viewport_to_picture_graphic(std::uint16_t graphicsContextObjectID, std::uint16_t objectID); // VT Querying /// @brief Sends the get attribute value message /// @param[in] objectID The object ID to query /// @param[in] attributeID The attribute object to query - /// @returns true if the message was sent successfully - bool send_get_attribute_value(std::uint16_t objectID, std::uint8_t attributeID) const; + /// @returns true if the message is being sent successfully + bool send_get_attribute_value(std::uint16_t objectID, std::uint8_t attributeID); // Get Softkeys Response /// @brief Returns the number of X axis pixels in a softkey @@ -1120,10 +1187,10 @@ namespace isobus /// @returns The VT version supported supported by the VT server VTVersion get_connected_vt_version() const; - /// @brief Returns if the VT version is supported by the VT server + /// @brief Returns whether the VT version is supported by the VT server /// @param[in] value The VT version to check against /// @returns true if the VT version is supported by the VT server - bool get_vt_version_supported(VTVersion value) const; + bool is_vt_version_supported(VTVersion value) const; /// @brief Returns the current data mask displayed by the VT server /// @returns The object ID of the data mask visible @@ -1140,7 +1207,7 @@ namespace isobus // You have a few options: // 1. Upload in one blob of contigious memory // This is good for small pools or pools where you have all the data in memory. - // 2. Get a callback at some inteval to provide data in chunks + // 2. Get a callback at some interval to provide data in chunks // This is probably better for huge pools if you are RAM constrained, or if your // pool is stored on some external device that you need to get data from in pages. // This is also the best way to load from IOP files! @@ -1150,12 +1217,10 @@ namespace isobus /// @brief Assigns an object pool to the client using a buffer and size. /// @details This is good for small pools or pools where you have all the data in memory. /// @param[in] poolIndex The index of the pool you are assigning - /// @param[in] poolSupportedVTVersion The VT version of the object pool /// @param[in] pool A pointer to the object pool. Must remain valid until client is connected! /// @param[in] size The object pool size /// @param[in] version An optional version string. The stack will automatically store/load your pool from the VT if this is provided. void set_object_pool(std::uint8_t poolIndex, - VTVersion poolSupportedVTVersion, const std::uint8_t *pool, std::uint32_t size, std::string version = ""); @@ -1163,11 +1228,9 @@ namespace isobus /// @brief Assigns an object pool to the client using a vector. /// @details This is good for small pools or pools where you have all the data in memory. /// @param[in] poolIndex The index of the pool you are assigning - /// @param[in] poolSupportedVTVersion The VT version of the object pool /// @param[in] pool A pointer to the object pool. Must remain valid until client is connected! /// @param[in] version An optional version string. The stack will automatically store/load your pool from the VT if this is provided. void set_object_pool(std::uint8_t poolIndex, - VTVersion poolSupportedVTVersion, const std::vector *pool, std::string version = ""); @@ -1184,11 +1247,10 @@ namespace isobus /// pool is stored on some external device that you need to get data from in pages. /// This is also the best way to load from IOP files, as you can read the data in piece by piece. /// @param[in] poolIndex The index of the pool you are assigning - /// @param[in] poolSupportedVTVersion The VT version of the object pool /// @param[in] poolTotalSize The object pool size /// @param[in] value The data callback that will be used to get object pool data to upload. /// @param[in] version An optional version string. The stack will automatically store/load your pool from the VT if this is provided. - void register_object_pool_data_chunk_callback(std::uint8_t poolIndex, VTVersion poolSupportedVTVersion, std::uint32_t poolTotalSize, DataChunkCallback value, std::string version = ""); + void register_object_pool_data_chunk_callback(std::uint8_t poolIndex, std::uint32_t poolTotalSize, DataChunkCallback value, std::string version = ""); /// @brief Periodic Update Function (worker thread may call this) /// @details This class can spawn a thread, or you can supply your own to run this function. @@ -1199,84 +1261,6 @@ namespace isobus LanguageCommandInterface languageCommandInterface; protected: - /// @brief Enumerates the multiplexor byte values for VT commands - enum class Function : std::uint8_t - { - SoftKeyActivationMessage = 0x00, - ButtonActivationMessage = 0x01, - PointingEventMessage = 0x02, - VTSelectInputObjectMessage = 0x03, - VTESCMessage = 0x04, - VTChangeNumericValueMessage = 0x05, - VTChangeActiveMaskMessage = 0x06, - VTChangeSoftKeyMaskMessage = 0x07, - VTChangeStringValueMessage = 0x08, - VTOnUserLayoutHideShowMessage = 0x09, - VTControlAudioSignalTerminationMessage = 0x0A, - ObjectPoolTransferMessage = 0x11, - EndOfObjectPoolMessage = 0x12, - AuxiliaryAssignmentTypeOneCommand = 0x20, - AuxiliaryInputTypeOneStatus = 0x21, - PreferredAssignmentCommand = 0x22, - AuxiliaryInputTypeTwoMaintenanceMessage = 0x23, - AuxiliaryAssignmentTypeTwoCommand = 0x24, - AuxiliaryInputStatusTypeTwoEnableCommand = 0x25, - AuxiliaryInputTypeTwoStatusMessage = 0x26, - AuxiliaryCapabilitiesRequest = 0x27, - SelectActiveWorkingSet = 0x90, - ESCCommand = 0x92, - HideShowObjectCommand = 0xA0, - EnableDisableObjectCommand = 0xA1, - SelectInputObjectCommand = 0xA2, - ControlAudioSignalCommand = 0xA3, - SetAudioVolumeCommand = 0xA4, - ChangeChildLocationCommand = 0xA5, - ChangeSizeCommand = 0xA6, - ChangeBackgroundColourCommand = 0xA7, - ChangeNumericValueCommand = 0xA8, - ChangeEndPointCommand = 0xA9, - ChangeFontAttributesCommand = 0xAA, - ChangeLineAttributesCommand = 0xAB, - ChangeFillAttributesCommand = 0xAC, - ChangeActiveMaskCommand = 0xAD, - ChangeSoftKeyMaskCommand = 0xAE, - ChangeAttributeCommand = 0xAF, - ChangePriorityCommand = 0xB0, - ChangeListItemCommand = 0xB1, - DeleteObjectPoolCommand = 0xB2, - ChangeStringValueCommand = 0xB3, - ChangeChildPositionCommand = 0xB4, - ChangeObjectLabelCommand = 0xB5, - ChangePolygonPointCommand = 0xB6, - ChangePolygonScaleCommand = 0xB7, - GraphicsContextCommand = 0xB8, - GetAttributeValueMessage = 0xB9, - SelectColourMapCommand = 0xBA, - IdentifyVTMessage = 0xBB, - ExecuteExtendedMacroCommand = 0xBC, - LockUnlockMaskCommand = 0xBD, - ExecuteMacroCommand = 0xBE, - GetMemoryMessage = 0xC0, - GetSupportedWidecharsMessage = 0xC1, - GetNumberOfSoftKeysMessage = 0xC2, - GetTextFontDataMessage = 0xC3, - GetWindowMaskDataMessage = 0xC4, - GetSupportedObjectsMessage = 0xC5, - GetHardwareMessage = 0xC7, - StoreVersionCommand = 0xD0, - LoadVersionCommand = 0xD1, - DeleteVersionCommand = 0xD2, - ExtendedGetVersionsMessage = 0xD3, - ExtendedStoreVersionCommand = 0xD4, - ExtendedLoadVersionCommand = 0xD5, - ExtendedDeleteVersionCommand = 0xD6, - GetVersionsMessage = 0xDF, - GetVersionsResponse = 0xE0, - UnsupportedVTFunctionMessage = 0xFD, - VTStatusMessage = 0xFE, - WorkingSetMaintenanceMessage = 0xFF - }; - /// @brief Enumerates the command types for graphics context objects enum class GraphicsContextSubCommandID : std::uint8_t { @@ -1332,7 +1316,6 @@ namespace isobus std::uint32_t objectPoolSize; ///< The size of the object pool std::uint32_t autoScaleDataMaskOriginalDimension; ///< The original length or width of this object pool's data mask area (in pixels) std::uint32_t autoScaleSoftKeyDesignatorOriginalHeight; ///< The original height of a soft key designator as designed in the pool (in pixels) - VTVersion version; ///< The version of the object pool. Must be the same for all pools! bool useDataCallback; ///< Determines if the client will use callbacks to get the data in chunks. bool uploaded; ///< The upload state of this pool }; @@ -1359,6 +1342,13 @@ namespace isobus static constexpr std::uint64_t AUXILIARY_INPUT_STATUS_DELAY = 1000; ///< The delay between the auxiliary input status messages, in milliseconds static constexpr std::uint64_t AUXILIARY_INPUT_STATUS_DELAY_INTERACTION = 50; ///< The delay between the auxiliary input status messages when the input is interacted with, in milliseconds + /// @brief Sends a message to the VT server + /// @param[in] dataBuffer A pointer to the data buffer to send + /// @param[in] dataLength The length of the data buffer + /// @param[in] priority The priority of the message (default is Priority5) + /// @returns true if the message was sent successfully, false otherwise + bool send_message_to_vt(const std::uint8_t *dataBuffer, std::uint32_t dataLength, CANIdentifier::CANPriority priority = CANIdentifier::CANPriority::Priority5) const; + // Object Pool Managment /// @brief Sends the delete object pool message /// @returns true if the message was sent @@ -1366,9 +1356,8 @@ namespace isobus /// @brief Sends the working set maintenance message /// @param[in] initializing Used to set the initializing bit - /// @param[in] workingSetVersion The version supported by the working set /// @returns true if the message was sent - bool send_working_set_maintenance(bool initializing, VTVersion workingSetVersion) const; + bool send_working_set_maintenance(bool initializing) const; /// @brief Sends the get memory message /// @details This message checks to see if the VT has enough memory available to store your object pool(s) @@ -1491,6 +1480,12 @@ namespace isobus static void process_rx_message(const CANMessage &message, void *parentPointer); /// @brief The callback passed to the network manager's send function to know when a Tx is completed + /// @param[in] parameterGroupNumber The parameter group number of the message that was sent + /// @param[in] dataLength The length of the data that was sent + /// @param[in] sourceControlFunction The control function that sent the message + /// @param[in] destinationControlFunction The control function that received the message or nullptr for a broadcast + /// @param[in] successful true if the message was sent successfully + /// @param[in] parentPointer A context variable to find the relevant VT client class static void process_callback(std::uint32_t parameterGroupNumber, std::uint32_t dataLength, std::shared_ptr sourceControlFunction, @@ -1522,6 +1517,7 @@ namespace isobus bool scale_object_pools(); /// @brief Returns if the specified object type can be scaled + /// @param[in] type The object type to check /// @returns true if the object is inherently scalable static bool get_is_object_scalable(VirtualTerminalObjectType type); @@ -1559,6 +1555,36 @@ namespace isobus /// @returns true if the object was resized, otherwise false bool resize_object(std::uint8_t *buffer, float scaleFactor, VirtualTerminalObjectType type); + /// @brief Extract from the cache whether a VT does not support a specific function + /// @param[in] function The function to check + /// @returns true if the VT doesn't support the function + bool is_function_unsupported(Function function) const; + + /// @brief Extract from the cache whether a VT does not support a specific function + /// @param[in] functionCode The code of the function to check + /// @returns true if the VT doesn't support the function + bool is_function_unsupported(std::uint8_t functionCode) const; + + /// @brief Sends a command to the VT server + /// @param[in] data The data to send, including the function-code + /// @returns true if the message was sent successfully + bool send_command(const std::vector &data); + + /// @brief Tries to send a command to the VT server, and queues it if it fails + /// @param[in] data The data to send, including the function-code + /// @param[in] replace If true, the message will replace any existing message with the same priority and function-code + /// @returns true if the message was sent/queued successfully + bool queue_command(const std::vector &data, bool replace = false); + + /// @brief Replaces the first message in the queue with the same function-code and priority, and removes the rest + /// @note This will not queue a message if one does not already exist. + /// @param[in] data The data to send, including the function-code + /// @returns true if the message was replaced successfully + bool replace_command(const std::vector &data); + + /// @brief Tries to send all messages in the queue + void process_command_queue(); + /// @brief The worker thread will execute this function when it runs, if applicable void worker_thread_function(); @@ -1605,6 +1631,7 @@ namespace isobus std::uint32_t lastWorkingSetMaintenanceTimestamp_ms = 0; ///< The timestamp from the last time we sent the maintenance message std::uint32_t lastAuxiliaryMaintenanceTimestamp_ms = 0; ///< The timestamp from the last time we sent the maintenance message std::vector objectPools; ///< A container to hold all object pools that have been assigned to the interface + std::vector unsupportedFunctions; ///< Holds the functions unsupported by the server. std::vector assignedAuxiliaryInputDevices; ///< A container to hold all auxiliary input devices known std::uint16_t ourModelIdentificationCode = 1; ///< The model identification code of this input device std::map ourAuxiliaryInputs; ///< The inputs on this auxiliary input device @@ -1617,6 +1644,14 @@ namespace isobus bool sendAuxiliaryMaintenance = false; ///< Used internally to enable and disable cyclic sending of the auxiliary maintenance message bool shouldTerminate = false; ///< Used to determine if the client should exit and join the worker thread + // Command queue + std::vector> commandQueue; ///< A queue of commands to send to the VT server + bool commandAwaitingResponse = false; ///< Determines if we are currently waiting for a response to a command + std::uint32_t lastCommandTimestamp_ms = 0; ///< The timestamp of the last command sent +#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO + std::mutex commandQueueMutex; ///< A mutex to protect the command queue +#endif + // Activation event callbacks EventDispatcher softKeyEventDispatcher; ///< A list of all soft key event callbacks EventDispatcher buttonEventDispatcher; ///< A list of all button event callbacks @@ -1638,4 +1673,23 @@ namespace isobus } // namespace isobus +// Required for FontSize to be used as a key in std::unordered_map, issue in C++11: https://cplusplus.github.io/LWG/issue2148 +#if __cplusplus < 201402L +namespace std +{ + /// @brief Hashes a font size + template<> + struct hash + { + /// @brief Hashes a font size + /// @param fontSize The font size to hash + /// @return The hash of the font size + size_t operator()(const isobus::VirtualTerminalClient::FontSize &fontSize) const + { + return static_cast(fontSize); + } + }; +} +#endif + #endif // ISOBUS_VIRTUAL_TERMINAL_CLIENT_HPP diff --git a/src/isobus_virtual_terminal_client_state_tracker.cpp b/src/isobus_virtual_terminal_client_state_tracker.cpp new file mode 100644 index 0000000..183aff0 --- /dev/null +++ b/src/isobus_virtual_terminal_client_state_tracker.cpp @@ -0,0 +1,396 @@ +//================================================================================================ +/// @file isobus_virtual_terminal_client_state_tracker.cpp +/// +/// @brief A helper class to track the state of an active working set. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ +#include "isobus_virtual_terminal_client_state_tracker.hpp" + +#include "can_general_parameter_group_numbers.hpp" +#include "can_network_manager.hpp" +#include "can_stack_logger.hpp" +#include "isobus_virtual_terminal_client.hpp" + +#include + +namespace isobus +{ + VirtualTerminalClientStateTracker::VirtualTerminalClientStateTracker(std::shared_ptr client) : + client(client) + { + } + + VirtualTerminalClientStateTracker::~VirtualTerminalClientStateTracker() + { + terminate(); + } + + void VirtualTerminalClientStateTracker::initialize() + { + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VirtualTerminalToECU), process_rx_or_tx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), process_rx_or_tx_message, this); + CANNetworkManager::CANNetwork.add_global_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VirtualTerminalToECU), process_rx_or_tx_message, this); + } + + void VirtualTerminalClientStateTracker::terminate() + { + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VirtualTerminalToECU), process_rx_or_tx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::ECUtoVirtualTerminal), process_rx_or_tx_message, this); + CANNetworkManager::CANNetwork.remove_global_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VirtualTerminalToECU), process_rx_or_tx_message, this); + } + + void VirtualTerminalClientStateTracker::add_tracked_numeric_value(std::uint16_t objectId, std::uint32_t initialValue) + { + if (numericValueStates.find(objectId) != numericValueStates.end()) + { + CANStackLogger::warn("[VTStateHelper] add_tracked_numeric_value: objectId '%lu' already tracked", objectId); + return; + } + + numericValueStates[objectId] = initialValue; + } + + void VirtualTerminalClientStateTracker::remove_tracked_numeric_value(std::uint16_t objectId) + { + if (numericValueStates.find(objectId) == numericValueStates.end()) + { + CANStackLogger::warn("[VTStateHelper] remove_tracked_numeric_value: objectId '%lu' was not tracked", objectId); + return; + } + + numericValueStates.erase(objectId); + } + + std::uint32_t VirtualTerminalClientStateTracker::get_numeric_value(std::uint16_t objectId) const + { + if (numericValueStates.find(objectId) == numericValueStates.end()) + { + CANStackLogger::warn("[VTStateHelper] get_numeric_value: objectId '%lu' not tracked", objectId); + return 0; + } + + return numericValueStates.at(objectId); + } + + std::uint16_t VirtualTerminalClientStateTracker::get_active_mask() const + { + return activeDataOrAlarmMask; + } + + const std::deque &VirtualTerminalClientStateTracker::get_mask_history() const + { + return dataAndAlarmMaskHistory; + } + + std::size_t VirtualTerminalClientStateTracker::get_max_mask_history_size() const + { + return maxDataAndAlarmMaskHistorySize; + } + + void VirtualTerminalClientStateTracker::set_max_mask_history_size(std::size_t size) + { + maxDataAndAlarmMaskHistorySize = size; + } + + void VirtualTerminalClientStateTracker::add_tracked_soft_key_mask(std::uint16_t dataOrAlarmMaskId, std::uint16_t initialSoftKeyMaskId) + { + if (softKeyMasks.find(dataOrAlarmMaskId) != softKeyMasks.end()) + { + CANStackLogger::warn("[VTStateHelper] add_tracked_soft_key_mask: data/alarm mask '%lu' already tracked", dataOrAlarmMaskId); + return; + } + + softKeyMasks[dataOrAlarmMaskId] = initialSoftKeyMaskId; + } + + void VirtualTerminalClientStateTracker::remove_tracked_soft_key_mask(std::uint16_t dataOrAlarmMaskId) + { + if (softKeyMasks.find(dataOrAlarmMaskId) == softKeyMasks.end()) + { + CANStackLogger::warn("[VTStateHelper] remove_tracked_soft_key_mask: data/alarm mask '%lu' was not tracked", dataOrAlarmMaskId); + return; + } + + softKeyMasks.erase(dataOrAlarmMaskId); + } + + std::uint16_t VirtualTerminalClientStateTracker::get_active_soft_key_mask() const + { + if (softKeyMasks.find(activeDataOrAlarmMask) == softKeyMasks.end()) + { + CANStackLogger::warn("[VTStateHelper] get_active_soft_key_mask: the currently active data/alarm mask '%lu' is not tracked", activeDataOrAlarmMask); + return NULL_OBJECT_ID; + } + + return softKeyMasks.at(activeDataOrAlarmMask); + } + + std::uint16_t VirtualTerminalClientStateTracker::get_soft_key_mask(std::uint16_t dataOrAlarmMaskId) const + { + if (softKeyMasks.find(dataOrAlarmMaskId) == softKeyMasks.end()) + { + CANStackLogger::warn("[VTStateHelper] get_soft_key_mask: data/alarm mask '%lu' is not tracked", activeDataOrAlarmMask); + return NULL_OBJECT_ID; + } + + return softKeyMasks.at(dataOrAlarmMaskId); + } + + bool VirtualTerminalClientStateTracker::is_working_set_active() const + { + return (client != nullptr) && client->get_address_valid() && (client->get_address() == activeWorkingSetAddress); + } + + void VirtualTerminalClientStateTracker::add_tracked_attribute(std::uint16_t objectId, std::uint8_t attribute, std::uint32_t initialValue) + { + if (attributeStates.find(objectId) == attributeStates.end()) + { + attributeStates[objectId] = {}; + } + + auto &attributeMap = attributeStates.at(objectId); + if (attributeMap.find(attribute) != attributeMap.end()) + { + CANStackLogger::warn("[VTStateHelper] add_tracked_attribute: attribute '%lu' of objectId '%lu' already tracked", attribute, objectId); + return; + } + + attributeMap[attribute] = initialValue; + } + + void VirtualTerminalClientStateTracker::remove_tracked_attribute(std::uint16_t objectId, std::uint8_t attribute) + { + if (attributeStates.find(objectId) == attributeStates.end()) + { + CANStackLogger::warn("[VTStateHelper] remove_tracked_attribute: objectId '%lu' was not tracked", objectId); + return; + } + + auto &attributeMap = attributeStates.at(objectId); + if (attributeMap.find(attribute) == attributeMap.end()) + { + CANStackLogger::warn("[VTStateHelper] remove_tracked_attribute: attribute '%lu' of objectId '%lu' was not tracked", attribute, objectId); + return; + } + + attributeMap.erase(attribute); + } + + std::uint32_t VirtualTerminalClientStateTracker::get_attribute(std::uint16_t objectId, std::uint8_t attribute) const + { + if (attributeStates.find(objectId) == attributeStates.end()) + { + CANStackLogger::warn("[VTStateHelper] get_attribute: objectId '%lu' not tracked", objectId); + return 0; + } + + const auto &attributeMap = attributeStates.at(objectId); + if (attributeMap.find(attribute) == attributeMap.end()) + { + CANStackLogger::warn("[VTStateHelper] get_attribute: attribute '%lu' of objectId '%lu' not tracked", attribute, objectId); + return 0; + } + + return attributeMap.at(attribute); + } + + void VirtualTerminalClientStateTracker::cache_active_mask(std::uint16_t maskId) + { + if (activeDataOrAlarmMask != maskId) + { + // Add the current active mask to the history if it is valid + if (activeDataOrAlarmMask != NULL_OBJECT_ID) + { + dataAndAlarmMaskHistory.push_front(activeDataOrAlarmMask); + if (dataAndAlarmMaskHistory.size() > maxDataAndAlarmMaskHistorySize) + { + dataAndAlarmMaskHistory.pop_back(); + } + } + // Update the active mask + activeDataOrAlarmMask = maskId; + } + } + + void VirtualTerminalClientStateTracker::process_rx_or_tx_message(const CANMessage &message, void *parentPointer) + { + if ((!message.has_valid_source_control_function()) || (message.get_data_length() == 0)) + { + // We are not interested in messages without a valid source control function or without data + return; + } + + auto *parent = static_cast(parentPointer); + if (message.is_broadcast() && + message.is_parameter_group_number(CANLibParameterGroupNumber::VirtualTerminalToECU) && + (message.get_uint8_at(0) == static_cast(VirtualTerminalClient::Function::VTStatusMessage))) + { + parent->process_status_message(message); + } + if (message.is_source(parent->server) && (!message.is_broadcast()) && message.is_parameter_group_number(CANLibParameterGroupNumber::VirtualTerminalToECU)) + { + parent->process_message_from_connected_server(message); + } + else if (message.is_destination(parent->server) && (!message.is_broadcast()) && message.is_parameter_group_number(CANLibParameterGroupNumber::ECUtoVirtualTerminal)) + { + parent->process_message_to_connected_server(message); + } + } + + void VirtualTerminalClientStateTracker::process_status_message(const CANMessage &message) + { + if (CAN_DATA_LENGTH == message.get_data_length()) + { + activeWorkingSetAddress = message.get_uint8_at(1); + if (is_working_set_active()) + { + server = message.get_source_control_function(); + cache_active_mask(message.get_uint16_at(2)); + if (softKeyMasks.find(activeDataOrAlarmMask) != softKeyMasks.end()) + { + std::uint16_t softKeyMask = message.get_uint16_at(4); + softKeyMasks[activeDataOrAlarmMask] = softKeyMask; + } + } + } + } + + void VirtualTerminalClientStateTracker::process_message_from_connected_server(const CANMessage &message) + { + std::uint8_t function = message.get_uint8_at(0); + switch (function) + { + case static_cast(VirtualTerminalClient::Function::VTStatusMessage): + { + server = message.get_source_control_function(); + activeWorkingSetAddress = message.get_uint8_at(1); + if (is_working_set_active()) + { + cache_active_mask(message.get_uint16_at(2)); + if (softKeyMasks.find(activeDataOrAlarmMask) != softKeyMasks.end()) + { + std::uint16_t softKeyMask = message.get_uint16_at(4); + softKeyMasks[activeDataOrAlarmMask] = softKeyMask; + } + } + } + break; + + case static_cast(VirtualTerminalClient::Function::ChangeActiveMaskCommand): + { + auto errorCode = message.get_uint8_at(3); + if (errorCode == 0) + { + cache_active_mask(message.get_uint16_at(1)); + } + } + break; + + case static_cast(VirtualTerminalClient::Function::ChangeSoftKeyMaskCommand): + { + auto errorCode = message.get_uint8_at(3); + if (errorCode == 0) + { + std::uint16_t associatedMask = message.get_uint16_at(1); + std::uint16_t softKeyMask = message.get_uint16_at(4); + if (softKeyMasks.find(associatedMask) != softKeyMasks.end()) + { + softKeyMasks[associatedMask] = softKeyMask; + } + } + } + break; + + case static_cast(VirtualTerminalClient::Function::ChangeNumericValueCommand): + { + if (CAN_DATA_LENGTH == message.get_data_length()) + { + auto errorCode = message.get_uint8_at(3); + if (errorCode == 0) + { + std::uint16_t objectId = message.get_uint16_at(1); + if (numericValueStates.find(objectId) != numericValueStates.end()) + { + std::uint32_t value = message.get_uint32_at(4); + numericValueStates[objectId] = value; + } + } + } + } + break; + + case static_cast(VirtualTerminalClient::Function::VTChangeNumericValueMessage): + { + if (CAN_DATA_LENGTH == message.get_data_length()) + { + std::uint16_t objectId = message.get_uint16_at(1); + if (numericValueStates.find(objectId) != numericValueStates.end()) + { + std::uint32_t value = message.get_uint32_at(4); + numericValueStates[objectId] = value; + } + } + } + break; + + case static_cast(VirtualTerminalClient::Function::ChangeAttributeCommand): + { + if (CAN_DATA_LENGTH == message.get_data_length()) + { + auto errorCode = message.get_uint8_at(4); + if (errorCode == 0) + { + std::uint16_t objectId = message.get_uint16_at(1); + std::uint8_t attribute = message.get_uint8_at(3); + std::uint8_t error = message.get_uint8_at(4); + + if (pendingChangeAttributeCommands.find(message.get_destination_control_function()) != pendingChangeAttributeCommands.end()) + { + const auto &pendingCommand = pendingChangeAttributeCommands.at(message.get_source_control_function()); + if ((pendingCommand.objectId == objectId) && (pendingCommand.attribute == attribute) && (0 == error)) + { + std::uint32_t value = message.get_uint32_at(5); + attributeStates[objectId][attribute] = value; + } + pendingChangeAttributeCommands.erase(message.get_destination_control_function()); + } + } + } + } + break; + + default: + break; + } + } + + void VirtualTerminalClientStateTracker::process_message_to_connected_server(const CANMessage &message) + { + std::uint8_t function = message.get_uint8_at(0); + switch (function) + { + case static_cast(VirtualTerminalClient::Function::ChangeAttributeCommand): + { + if (CAN_DATA_LENGTH == message.get_data_length()) + { + std::uint16_t objectId = message.get_uint16_at(1); + std::uint8_t attribute = message.get_uint8_at(3); + + // Only track the change if the attribute should be tracked + if ((attributeStates.find(objectId) != attributeStates.end()) && + (attributeStates.at(objectId).find(attribute) != attributeStates.at(objectId).end())) + { + std::uint32_t value = message.get_uint32_at(4); + pendingChangeAttributeCommands[message.get_source_control_function()] = { value, objectId, attribute }; + } + } + } + break; + + default: + break; + } + } +} // namespace isobus diff --git a/src/isobus_virtual_terminal_client_state_tracker.hpp b/src/isobus_virtual_terminal_client_state_tracker.hpp new file mode 100644 index 0000000..d2f5e5b --- /dev/null +++ b/src/isobus_virtual_terminal_client_state_tracker.hpp @@ -0,0 +1,180 @@ +//================================================================================================ +/// @file isobus_virtual_terminal_client_state_tracker.hpp +/// +/// @brief A helper class to track the state of an active working set. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ + +#ifndef ISOBUS_VIRTUAL_TERMINAL_CLIENT_STATE_TRACKER_HPP +#define ISOBUS_VIRTUAL_TERMINAL_CLIENT_STATE_TRACKER_HPP + +#include "can_constants.hpp" +#include "can_control_function.hpp" +#include "can_message.hpp" + +#include +#include +#include + +namespace isobus +{ + /// @brief A helper class to update and track the state of an active working set. + /// @details The state is from the client's perspective. It might not be the same + /// as the state of the server, but tries to be as close as possible. + class VirtualTerminalClientStateTracker + { + public: + /// @brief The constructor to track the state of an active working set provided by a client. + /// @param[in] client The control function of the client. May be external. + explicit VirtualTerminalClientStateTracker(std::shared_ptr client); + + /// @brief The destructor. + ~VirtualTerminalClientStateTracker(); + + /// @brief Initializes the state tracker. + void initialize(); + + /// @brief Terminate the state tracker. + void terminate(); + + //! TODO: void initialize_with_defaults(ObjectPool &objectPool); + + /// @brief Adds a numeric value to track. + /// @param[in] objectId The object id of the numeric value to track. + /// @param[in] initialValue The initial value of the numeric value to track. + void add_tracked_numeric_value(std::uint16_t objectId, std::uint32_t initialValue = 0); + + /// @brief Removes a numeric value from tracking. + /// @param[in] objectId The object id of the numeric value to remove from tracking. + void remove_tracked_numeric_value(std::uint16_t objectId); + + /// @brief Gets the current numeric value of a tracked object. + /// @param[in] objectId The object id of the numeric value to get. + /// @return The current numeric value of the tracked object. + std::uint32_t get_numeric_value(std::uint16_t objectId) const; + + /// @brief Get the data/alarm mask currently active on the server for this client. It may not be displayed if the working set is not active. + /// @return The data/alarm mask currently active on the server for this client. + std::uint16_t get_active_mask() const; + + /// @brief Get the history of data/alarm masks that were active on the server for this client. + /// @return The history of data/alarm masks that were active on the server for this client. + const std::deque &get_mask_history() const; + + /// @brief Get the maximum size of the data/alarm mask history. + /// @return The maximum size of the data/alarm mask history. + std::size_t get_max_mask_history_size() const; + + /// @brief Sets the maximum size of the data/alarm mask history (default: 100) + /// @param[in] size The maximum size of the data/alarm mask history. + void set_max_mask_history_size(std::size_t size); + + /// @brief Adds a data/alarm mask to track the soft key mask for. + /// @param[in] dataOrAlarmMaskId The data/alarm mask to track the soft key mask for. + /// @param[in] initialSoftKeyMaskId The initial soft key mask to associate with the data/alarm mask. + void add_tracked_soft_key_mask(std::uint16_t dataOrAlarmMaskId, std::uint16_t initialSoftKeyMaskId = 0); + + /// @brief Removes a data/alarm mask from tracking the soft key mask for. + /// @param[in] dataOrAlarmMaskId The data/alarm mask to remove the soft key mask from tracking for. + void remove_tracked_soft_key_mask(std::uint16_t dataOrAlarmMaskId); + + /// @brief Get the soft key mask currently active on thse server for this client. It may not be displayed if the working set is not active. + /// @return The soft key mask currently active on the server for this client. + std::uint16_t get_active_soft_key_mask() const; + + /// @brief Get the soft key mask currently associated with a data/alarm mask. + /// @param[in] dataOrAlarmMaskId The data/alarm mask to get the currently associated soft key mask for. + /// @return The soft key mask currently associated with the supplied mask. + std::uint16_t get_soft_key_mask(std::uint16_t dataOrAlarmMaskId) const; + + /// @brief Get whether the working set of the client is active on the server. + /// @return True if the working set is active, false otherwise. + bool is_working_set_active() const; + + /// @brief Adds an attribute to track. + /// @param[in] objectId The object id of the attribute to track. + /// @param[in] attribute The attribute to track. + /// @param[in] initialValue The initial value of the attribute to track. + void add_tracked_attribute(std::uint16_t objectId, std::uint8_t attribute, std::uint32_t initialValue = 0); + + /// @brief Removes an attribute from tracking. + /// @param[in] objectId The object id of the attribute to remove from tracking. + /// @param[in] attribute The attribute to remove from tracking. + void remove_tracked_attribute(std::uint16_t objectId, std::uint8_t attribute); + + /// @brief Get the value of an attribute of a tracked object. + /// @param[in] objectId The object id of the attribute to get. + /// @param[in] attribute The attribute to get. + /// @return The value of the attribute of the tracked object. + std::uint32_t get_attribute(std::uint16_t objectId, std::uint8_t attribute) const; + + protected: + std::shared_ptr client; ///< The control function of the virtual terminal client to track. + std::shared_ptr server; ///< The control function of the server the client is connected to. + + //! TODO: std::map shownStates; ///< Holds the 'hide/show' state of tracked objects. + //! TODO: std::map enabledStates; ///< Holds the 'enable/disable' state of tracked objects. + //! TODO: std::map selectedStates; ///< Holds the 'selected for input' state of tracked objects. + //! TODO: add current audio signal state + //! TODO: std::uint8_t audioVolumeState; ///< Holds the current audio volume. + //! TODO: std::map> positionStates; ///< Holds the 'position (x,y)' state of tracked objects. + //! TODO: std::map> sizeStates; ///< Holds the 'size (width,height)' state of tracked objects. + //! TODO: std::map backgroundColourStates; ///< Holds the 'background colour' state of tracked objects. + std::map numericValueStates; ///< Holds the 'numeric value' state of tracked objects. + //! TODO: std::map stringValueStates; ///< Holds the 'string value' state of tracked objects. + //! TODO: std::map endPointStates; ///< Holds the 'end point' state of tracked objects. + //! TODO: add font attribute state + //! TODO: add line attribute state + //! TODO: add fill attribute state + std::uint16_t activeDataOrAlarmMask = NULL_OBJECT_ID; ///< Holds the data/alarm mask currently visible on the server for this client. + std::deque dataAndAlarmMaskHistory; ///< Holds the history of data/alarm masks that were active on the server for this client. + std::size_t maxDataAndAlarmMaskHistorySize = 100; ///< Holds the maximum size of the data/alarm mask history. + std::uint8_t activeWorkingSetAddress = NULL_CAN_ADDRESS; ///< Holds the address of the control function that currently has + std::map softKeyMasks; ///< Holds the data/alarms masks with their associated soft keys masks for tracked objects. + std::map> attributeStates; ///< Holds the 'attribute' state of tracked objects. + //! TODO: std::map alarmMaskPrioritiesStates; ///< Holds the 'alarm mask priority' state of tracked objects. + //! TODO: std::map> listItemStates; ///< Holds the 'list item' state of tracked objects. + //! TODO: add lock/unlock mask state + //! TODO: add object label state + //! TODO: add polygon point state + //! TODO: add polygon scale state + //! TODO: add graphics context state + //! TODO: std::uint16_t currentColourMap; ///< Holds the current colour map/palette object. + + private: + /// @brief Cache a mask as the active mask on the server. + /// @param[in] maskId The mask to cache as the active mask on the server. + void cache_active_mask(std::uint16_t maskId); + + /// @brief Processes a received or transmitted message. + /// @param[in] message The message to process. + /// @param[in] parentPointer The pointer to the parent object, which should be the VirtualTerminalClientStateTracker. + static void process_rx_or_tx_message(const CANMessage &message, void *parentPointer); + + /// @brief Processes a status message from a VT server. + /// @param[in] message The message to process. + void process_status_message(const CANMessage &message); + + /// @brief Processes a VT->ECU message received by any client, sent from the connected server. + /// @param[in] message The message to process. + void process_message_from_connected_server(const CANMessage &message); + + /// @brief Processes a ECU->VT message received by the connected server, sent from any control function. + /// @param[in] message The message to process. + void process_message_to_connected_server(const CANMessage &message); + + /// @brief Data structure to hold the properties of a change attribute command + struct ChangeAttributeCommand + { + std::uint32_t value; ///< Holds the value to change the attribute to. + std::uint16_t objectId; ///< Holds the id of to be changed object. + std::uint8_t attribute; ///< Holds the id of the attribute to be changed of the specified object. + }; + + std::map, ChangeAttributeCommand> pendingChangeAttributeCommands; ///< Holds the pending change attribute command for a control function. + }; +} // namespace isobus + +#endif // ISOBUS_VIRTUAL_TERMINAL_CLIENT_STATE_TRACKER_HPP diff --git a/src/isobus_virtual_terminal_client_update_helper.cpp b/src/isobus_virtual_terminal_client_update_helper.cpp new file mode 100644 index 0000000..642a4ed --- /dev/null +++ b/src/isobus_virtual_terminal_client_update_helper.cpp @@ -0,0 +1,175 @@ +//================================================================================================ +/// @file isobus_virtual_terminal_client_update_helper.cpp +/// +/// @brief A helper class to update and track the state of an active working set. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ + +#include "isobus_virtual_terminal_client_update_helper.hpp" + +#include "can_stack_logger.hpp" + +namespace isobus +{ + VirtualTerminalClientUpdateHelper::VirtualTerminalClientUpdateHelper(std::shared_ptr client) : + VirtualTerminalClientStateTracker(nullptr == client ? nullptr : client->get_internal_control_function()), + vtClient(client) + { + if (nullptr == client) + { + CANStackLogger::error("[VTStateHelper] constructor: client is nullptr"); + return; + } + numericValueChangeEventHandle = client->get_vt_change_numeric_value_event_dispatcher().add_listener( + std::bind(&VirtualTerminalClientUpdateHelper::process_numeric_value_change_event, this, std::placeholders::_1)); + } + + VirtualTerminalClientUpdateHelper::~VirtualTerminalClientUpdateHelper() + { + if (nullptr != vtClient) + { + vtClient->get_vt_change_numeric_value_event_dispatcher().remove_listener(numericValueChangeEventHandle); + } + } + + bool VirtualTerminalClientUpdateHelper::set_numeric_value(std::uint16_t object_id, std::uint32_t value) + { + if (nullptr == client) + { + CANStackLogger::error("[VTStateHelper] set_numeric_value: client is nullptr"); + return false; + } + if (numericValueStates.find(object_id) == numericValueStates.end()) + { + CANStackLogger::warn("[VTStateHelper] set_numeric_value: objectId %lu not tracked", object_id); + return false; + } + if (numericValueStates.at(object_id) == value) + { + return true; + } + + bool success = vtClient->send_change_numeric_value(object_id, value); + if (success) + { + numericValueStates[object_id] = value; + } + return success; + } + + bool VirtualTerminalClientUpdateHelper::increase_numeric_value(std::uint16_t object_id, std::uint32_t step) + { + return set_numeric_value(object_id, get_numeric_value(object_id) + step); + } + + bool VirtualTerminalClientUpdateHelper::decrease_numeric_value(std::uint16_t object_id, std::uint32_t step) + { + return set_numeric_value(object_id, get_numeric_value(object_id) - step); + } + + void VirtualTerminalClientUpdateHelper::set_callback_validate_numeric_value(const std::function &callback) + { + callbackValidateNumericValue = callback; + } + + void VirtualTerminalClientUpdateHelper::process_numeric_value_change_event(const VirtualTerminalClient::VTChangeNumericValueEvent &event) + { + if (numericValueStates.find(event.objectID) == numericValueStates.end()) + { + // Only proccess numeric value changes for tracked objects. + return; + } + + if (numericValueStates.at(event.objectID) == event.value) + { + // Do not process the event if the value has not changed. + return; + } + + std::uint32_t targetValue = event.value; // Default to the value received in the event. + if ((callbackValidateNumericValue != nullptr) && callbackValidateNumericValue(event.objectID, event.value)) + { + // If the callback function returns false, reject the change by sending the previous value. + targetValue = numericValueStates.at(event.objectID); + } + vtClient->send_change_numeric_value(event.objectID, targetValue); + } + + bool VirtualTerminalClientUpdateHelper::set_active_data_or_alarm_mask(std::uint16_t workingSetId, std::uint16_t dataOrAlarmMaskId) + { + if (nullptr == client) + { + CANStackLogger::error("[VTStateHelper] set_active_data_or_alarm_mask: client is nullptr"); + return false; + } + if (activeDataOrAlarmMask == dataOrAlarmMaskId) + { + return true; + } + + bool success = vtClient->send_change_active_mask(workingSetId, dataOrAlarmMaskId); + if (success) + { + activeDataOrAlarmMask = dataOrAlarmMaskId; + } + return success; + } + + bool VirtualTerminalClientUpdateHelper::set_active_soft_key_mask(VirtualTerminalClient::MaskType maskType, std::uint16_t maskId, std::uint16_t softKeyMaskId) + { + if (nullptr == client) + { + CANStackLogger::error("[VTStateHelper] set_active_soft_key_mask: client is nullptr"); + return false; + } + if (softKeyMasks.find(maskId) == softKeyMasks.end()) + { + CANStackLogger::warn("[VTStateHelper] set_active_soft_key_mask: data/alarm mask '%lu' not tracked", maskId); + return false; + } + if (softKeyMasks.at(maskId) == softKeyMaskId) + { + return true; + } + + bool success = vtClient->send_change_softkey_mask(maskType, maskId, softKeyMaskId); + if (success) + { + softKeyMasks[maskId] = softKeyMaskId; + } + return success; + } + + bool VirtualTerminalClientUpdateHelper::set_attribute(std::uint16_t objectId, std::uint8_t attribute, std::uint32_t value) + { + if (nullptr == client) + { + CANStackLogger::error("[VTStateHelper] set_attribute: client is nullptr"); + return false; + } + if (attributeStates.find(objectId) == attributeStates.end()) + { + CANStackLogger::warn("[VTStateHelper] set_attribute: objectId %lu not tracked", objectId); + return false; + } + if (attributeStates.at(objectId).find(attribute) == attributeStates.at(objectId).end()) + { + CANStackLogger::warn("[VTStateHelper] set_attribute: attribute %lu of objectId %lu not tracked", attribute, objectId); + return false; + } + if (attributeStates.at(objectId).at(attribute) == value) + { + return true; + } + + bool success = vtClient->send_change_attribute(objectId, attribute, value); + if (success) + { + attributeStates[objectId][attribute] = value; + } + return success; + } + +} // namespace isobus diff --git a/src/isobus_virtual_terminal_client_update_helper.hpp b/src/isobus_virtual_terminal_client_update_helper.hpp new file mode 100644 index 0000000..2e5bdf4 --- /dev/null +++ b/src/isobus_virtual_terminal_client_update_helper.hpp @@ -0,0 +1,89 @@ +//================================================================================================ +/// @file isobus_virtual_terminal_client_update_helper.hpp +/// +/// @brief A helper class to update and track the state of an active working set. +/// @author Daan Steenbergen +/// +/// @copyright 2023 The Open-Agriculture Developers +//================================================================================================ + +#ifndef ISOBUS_VIRTUAL_TERMINAL_CLIENT_UPDATE_HELPER_HPP +#define ISOBUS_VIRTUAL_TERMINAL_CLIENT_UPDATE_HELPER_HPP + +#include "isobus_virtual_terminal_client.hpp" +#include "isobus_virtual_terminal_client_state_tracker.hpp" + +namespace isobus +{ + /// @brief A helper class to update and track the state of an active working set. + class VirtualTerminalClientUpdateHelper : public VirtualTerminalClientStateTracker + { + public: + /// @brief The constructor of class to help update the state of an active working set. + /// @param[in] client The virtual terminal client that provides the active working set. + explicit VirtualTerminalClientUpdateHelper(std::shared_ptr client); + + /// @brief The destructor of class to unregister event listeners. + ~VirtualTerminalClientUpdateHelper(); + + /// @brief Sets the numeric value of a tracked object. + /// @param[in] objectId The object id of the numeric value to set. + /// @param[in] value The value to set the numeric value to. + /// @return True if the value was set successfully, false otherwise. + bool set_numeric_value(std::uint16_t objectId, std::uint32_t value); + + /// @brief Increases the numeric value of a tracked object. + /// @param[in] objectId The object id of the numeric value to increase. + /// @param[in] step The step size to increase the numeric value with. + /// @return True if the value was increased successfully, false otherwise. + bool increase_numeric_value(std::uint16_t objectId, std::uint32_t step = 1); + + /// @brief Decreases the numeric value of a tracked object. + /// @param[in] objectId The object id of the numeric value to decrease. + /// @param[in] step The step size to decrease the numeric value with. + /// @return True if the value was decreased successfully, false otherwise. + bool decrease_numeric_value(std::uint16_t objectId, std::uint32_t step = 1); + + /// @brief Register a callback function to validate a numeric value change of a tracked object. + /// If the callback function returns true, the numeric value change will be acknowledged. + /// Otherwise, if the callback function returns false, the numeric value change will + /// be rejected by sending the current value back to the VT. + /// @param[in] callback The callback function to register, or nullptr to unregister. + void set_callback_validate_numeric_value(const std::function &callback); + + /// @brief Sets the active data/alarm mask. + /// @param[in] workingSetId The working set to set the active data/alarm mask for. + /// @param[in] dataOrAlarmMaskId The data/alarm mask to set active. + /// @return True if the data/alarm mask was set active successfully, false otherwise. + bool set_active_data_or_alarm_mask(std::uint16_t workingSetId, std::uint16_t dataOrAlarmMaskId); + + /// @brief Sets the active soft key mask. + /// @param[in] maskType The type of mask to set the active soft key mask for. + /// @param[in] maskId The mask to set the active soft key mask for. + /// @param[in] softKeyMaskId The soft key mask to set active. + /// @return True if the soft key mask was set active successfully, false otherwise. + bool set_active_soft_key_mask(VirtualTerminalClient::MaskType maskType, std::uint16_t maskId, std::uint16_t softKeyMaskId); + + /// @brief Sets the value of an attribute of a tracked object. + /// @note If the to be tracked working set consists of more than the master, + /// this function is incompatible with a VT prior to version 4. For working sets consisting + /// of only the master, this function is compatible with any VT version. + /// @param[in] objectId The object id of the attribute to set. + /// @param[in] attribute The attribute to set. + /// @param[in] value The value to set the attribute to. + /// @return True if the attribute was set successfully, false otherwise. + bool set_attribute(std::uint16_t objectId, std::uint8_t attribute, std::uint32_t value); + + private: + /// @brief Processes a numeric value change event + /// @param[in] event The numeric value change event to process. + void process_numeric_value_change_event(const VirtualTerminalClient::VTChangeNumericValueEvent &event); + + std::shared_ptr vtClient; ///< Holds the vt client. + + std::function callbackValidateNumericValue; ///< Holds the callback function to validate a numeric value change. + EventCallbackHandle numericValueChangeEventHandle; ///< Holds the handle to the numeric value change event listener + }; +} // namespace isobus + +#endif // ISOBUS_VIRTUAL_TERMINAL_CLIENT_UPDATE_HELPER_HPP diff --git a/src/isobus_virtual_terminal_objects.cpp b/src/isobus_virtual_terminal_objects.cpp new file mode 100644 index 0000000..0e8a728 --- /dev/null +++ b/src/isobus_virtual_terminal_objects.cpp @@ -0,0 +1,8832 @@ +//================================================================================================ +/// @file isobus_virtual_terminal_objects.cpp +/// +/// @brief Implements VT server object pool objects. +/// @author Adrian Del Grosso +/// +/// @copyright 2023 Adrian Del Grosso +//================================================================================================ +#include "isobus_virtual_terminal_objects.hpp" + +namespace isobus +{ + VTColourTable::VTColourTable() + { + // The table can be altered at runtime. Init here to VT standard + colourTable[0] = VTColourVector(0.0f, 0.0f, 0.0f); // Black + colourTable[1] = VTColourVector(1.0f, 1.0f, 1.0f); // White + colourTable[2] = VTColourVector(0.0f, (153.0f / 255.0f), 0.0f); // Green + colourTable[3] = VTColourVector(0.0f, (153.0f / 255.0f), (153.0f / 255.0f)); // Teal + colourTable[4] = VTColourVector((153.0f / 255.0f), 0.0f, 0.0f); // Maroon + colourTable[5] = VTColourVector((153.0f / 255.0f), 0.0f, (153.0f / 255.0f)); // Purple + colourTable[6] = VTColourVector((153.0f / 255.0f), (153.0f / 255.0f), 0.0f); // Olive + colourTable[7] = VTColourVector((204.0f / 255.0f), (204.0f / 255.0f), (204.0f / 255.0f)); // Silver + colourTable[8] = VTColourVector((153.0f / 255.0f), (153.0f / 255.0f), (153.0f / 255.0f)); // Grey + colourTable[9] = VTColourVector(0.0f, 0.0f, 1.0f); // Blue + colourTable[10] = VTColourVector(0.0f, 1.0f, 0.0f); // Lime + colourTable[11] = VTColourVector(0.0f, 1.0f, 1.0f); // Cyan + colourTable[12] = VTColourVector(1.0f, 0.0f, 0.0f); // Red + colourTable[13] = VTColourVector(1.0f, 0.0f, 1.0f); // Magenta + colourTable[14] = VTColourVector(1.0f, 1.0f, 0.0f); // Yellow + colourTable[15] = VTColourVector(0.0f, 0.0f, (153.0f / 255.0f)); // Navy + + // This section of the table increases with a pattern + for (std::uint8_t i = 16; i <= 231; i++) + { + std::uint8_t index = i - 16; + + std::uint32_t redCounter = (index / 36); + std::uint32_t greenCounter = ((index / 6) % 6); + std::uint32_t blueCounter = (index % 6); + + colourTable[i] = VTColourVector((51.0f * (redCounter) / 255.0f), ((51.0f * (greenCounter)) / 255.0f), ((51.0f * blueCounter) / 255.0f)); + } + + // The rest are proprietary. Init to white for now. + for (std::uint16_t i = 232; i < VT_COLOUR_TABLE_SIZE; i++) + { + colourTable[i] = VTColourVector(1.0f, 1.0f, 1.0f); + } + } + + VTColourVector VTColourTable::get_colour(std::uint8_t colourIndex) const + { + return colourTable.at(colourIndex); + } + + void VTColourTable::set_colour(std::uint8_t colourIndex, VTColourVector newColour) + { + colourTable.at(colourIndex) = newColour; + } + + std::uint16_t VTObject::get_id() const + { + return objectID; + } + + void VTObject::set_id(std::uint16_t value) + { + objectID = value; + } + + std::uint16_t VTObject::get_width() const + { + return width; + } + + void VTObject::set_width(std::uint16_t value) + { + width = value; + } + + std::uint16_t VTObject::get_height() const + { + return height; + } + + void VTObject::set_height(std::uint16_t value) + { + height = value; + } + + std::uint8_t VTObject::get_background_color() const + { + return backgroundColor; + } + + void VTObject::set_background_color(std::uint8_t value) + { + backgroundColor = value; + } + + std::uint16_t VTObject::get_number_children() const + { + return static_cast(children.size()); + } + + void VTObject::add_child(std::uint16_t objectID, std::int16_t relativeXLocation, std::int16_t relativeYLocation) + { + children.push_back(ChildObjectData(objectID, relativeXLocation, relativeYLocation)); + } + + std::uint16_t VTObject::get_child_id(std::uint16_t index) const + { + std::uint16_t retVal = NULL_OBJECT_ID; + + if (index < children.size()) + { + retVal = children[index].id; + } + return retVal; + } + + std::int16_t VTObject::get_child_x(std::uint16_t index) const + { + std::int16_t retVal = 0; + + if (index < children.size()) + { + retVal = children[index].xLocation; + } + return retVal; + } + + std::int16_t VTObject::get_child_y(std::uint16_t index) const + { + std::int16_t retVal = 0; + + if (index < children.size()) + { + retVal = children[index].yLocation; + } + return retVal; + } + + void VTObject::set_child_x(std::uint16_t index, std::int16_t xOffset) + { + if (index < children.size()) + { + children.at(index).xLocation = xOffset; + } + } + + void VTObject::set_child_y(std::uint16_t index, std::int16_t yOffset) + { + if (index < children.size()) + { + children.at(index).yLocation = yOffset; + } + } + + bool VTObject::offset_all_children_with_id(std::uint16_t childObjectID, std::int8_t xOffset, std::int8_t yOffset) + { + bool retVal = false; + + for (auto &child : children) + { + if (child.id == childObjectID) + { + child.xLocation += xOffset; + child.yLocation += yOffset; + } + } + return retVal; + } + + void VTObject::remove_child(std::uint16_t objectIDToRemove, std::int16_t relativeXLocation, std::int16_t relativeYLocation) + { + for (auto child = children.begin(); child != children.end(); child++) + { + if ((child->id == objectIDToRemove) && (child->xLocation == relativeXLocation) && (child->yLocation == relativeYLocation)) + { + children.erase(child); + break; + } + } + } + + void VTObject::pop_child() + { + if (!children.empty()) + { + children.pop_back(); + } + } + + std::uint8_t VTObject::get_number_macros() const + { + return static_cast(macros.size()); + } + + void VTObject::add_macro(MacroMetadata macroToAdd) + { + macros.push_back(macroToAdd); + } + + MacroMetadata VTObject::get_macro(std::uint8_t index) const + { + if (index < macros.size()) + { + return macros[index]; + } + else + { + return { EventID::Reserved, NULL_OBJECT_ID }; + } + } + + std::shared_ptr VTObject::get_object_by_id(std::uint16_t objectID, const std::map> &objectPool) + { + std::shared_ptr retVal = nullptr; + + if ((NULL_OBJECT_ID != objectID) && (objectPool.find(objectID) != objectPool.end())) + { + auto object = objectPool.at(objectID); + if (nullptr != object) + { + retVal = object; + } + } + return retVal; + } + + VTObject::ChildObjectData::ChildObjectData(std::uint16_t objectId, + std::int16_t x, + std::int16_t y) : + id(objectId), + xLocation(x), + yLocation(y) + { + } + + VirtualTerminalObjectType WorkingSet::get_object_type() const + { + return VirtualTerminalObjectType::WorkingSet; + } + + std::uint32_t WorkingSet::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool WorkingSet::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + { + // Valid Objects + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool WorkingSet::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Selectable: + { + set_selectable(0 != rawAttributeData); + retVal = true; + } + break; + + case AttributeName::ActiveMask: + { + set_active_mask(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool WorkingSet::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::Selectable): + { + returnedAttributeData = get_selectable(); + retVal = true; + } + break; + + case static_cast(AttributeName::ActiveMask): + { + returnedAttributeData = get_active_mask(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool WorkingSet::get_selectable() const + { + return selectable; + } + + void WorkingSet::set_selectable(bool value) + { + selectable = value; + } + + std::uint16_t WorkingSet::get_active_mask() const + { + return activeMask; + } + + void WorkingSet::set_active_mask(std::uint16_t value) + { + activeMask = value; + } + + VirtualTerminalObjectType DataMask::get_object_type() const + { + return VirtualTerminalObjectType::DataMask; + } + + std::uint32_t DataMask::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool DataMask::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + std::uint8_t numberOfSoftKeyMasks = 0; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Button: + case VirtualTerminalObjectType::InputBoolean: + case VirtualTerminalObjectType::InputString: + case VirtualTerminalObjectType::InputNumber: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::InputList: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::AuxiliaryFunctionType2: + case VirtualTerminalObjectType::AuxiliaryInputType2: + case VirtualTerminalObjectType::AuxiliaryControlDesignatorType2: + case VirtualTerminalObjectType::Macro: + { + // Valid Objects + } + break; + + case VirtualTerminalObjectType::SoftKeyMask: + { + // Valid Objects + numberOfSoftKeyMasks++; + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + + if (numberOfSoftKeyMasks > 1) + { + anyWrongChildType = true; + } + } + } + + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool DataMask::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(DataMask::AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case DataMask::AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case DataMask::AttributeName::SoftKeyMask: + { + returnedError = AttributeError::InvalidAttributeID; + retVal = change_soft_key_mask(static_cast(rawAttributeData), objectPool); + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool DataMask::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::SoftKeyMask): + { + returnedAttributeData = get_soft_key_mask(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool DataMask::change_soft_key_mask(std::uint16_t newMaskID, const std::map> &objectPool) + { + bool retVal = false; + + if (NULL_OBJECT_ID == newMaskID) + { + set_soft_key_mask(newMaskID); + retVal = true; + } + else if ((objectPool.end() != objectPool.find(newMaskID)) && + (nullptr != objectPool.at(newMaskID)) && + (VirtualTerminalObjectType::SoftKeyMask == objectPool.at(newMaskID)->get_object_type())) + { + set_soft_key_mask(newMaskID); + retVal = true; + } + return retVal; + } + + void DataMask::set_soft_key_mask(std::uint16_t newMaskID) + { + softKeyMaskObjectID = newMaskID; + } + + std::uint16_t DataMask::get_soft_key_mask() const + { + return softKeyMaskObjectID; + } + + VirtualTerminalObjectType AlarmMask::get_object_type() const + { + return VirtualTerminalObjectType::AlarmMask; + } + + std::uint32_t AlarmMask::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool AlarmMask::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Button: + case VirtualTerminalObjectType::InputBoolean: + case VirtualTerminalObjectType::InputString: + case VirtualTerminalObjectType::InputNumber: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::InputList: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::AuxiliaryFunctionType2: + case VirtualTerminalObjectType::AuxiliaryInputType2: + case VirtualTerminalObjectType::AuxiliaryControlDesignatorType2: + case VirtualTerminalObjectType::Macro: + case VirtualTerminalObjectType::SoftKeyMask: + { + // Valid Objects + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool AlarmMask::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AlarmMask::AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AlarmMask::AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AlarmMask::AttributeName::SoftKeyMask: + { + returnedError = AttributeError::AnyOtherError; + retVal = change_soft_key_mask(static_cast(rawAttributeData), objectPool); + } + break; + + case AlarmMask::AttributeName::Priority: + { + if (rawAttributeData <= static_cast(AlarmMask::Priority::Low)) + { + set_mask_priority(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + case AlarmMask::AttributeName::AcousticSignal: + { + if (rawAttributeData <= static_cast(AlarmMask::AcousticSignal::None)) + { + set_signal_priority(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool AlarmMask::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::SoftKeyMask): + { + returnedAttributeData = get_soft_key_mask(); + retVal = true; + } + break; + + case static_cast(AttributeName::Priority): + { + returnedAttributeData = static_cast(get_mask_priority()); + retVal = true; + } + break; + + case static_cast(AttributeName::AcousticSignal): + { + returnedAttributeData = static_cast(get_signal_priority()); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + AlarmMask::Priority AlarmMask::get_mask_priority() const + { + return maskPriority; + } + + void AlarmMask::set_mask_priority(Priority value) + { + maskPriority = value; + } + + AlarmMask::AcousticSignal AlarmMask::get_signal_priority() const + { + return signalPriority; + } + + void AlarmMask::set_signal_priority(AcousticSignal value) + { + signalPriority = value; + } + + bool AlarmMask::change_soft_key_mask(std::uint16_t newMaskID, const std::map> &objectPool) + { + bool retVal = false; + + if (NULL_OBJECT_ID == newMaskID) + { + set_soft_key_mask(newMaskID); + retVal = true; + } + else if ((nullptr != objectPool.at(newMaskID)) && + (VirtualTerminalObjectType::SoftKeyMask == objectPool.at(newMaskID)->get_object_type())) + { + set_soft_key_mask(newMaskID); + retVal = true; + } + return retVal; + } + + void AlarmMask::set_soft_key_mask(std::uint16_t newMaskID) + { + softKeyMask = newMaskID; + } + + std::uint16_t AlarmMask::get_soft_key_mask() const + { + return softKeyMask; + } + + VirtualTerminalObjectType Container::get_object_type() const + { + return VirtualTerminalObjectType::Container; + } + + std::uint32_t Container::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool Container::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::Button: + case VirtualTerminalObjectType::InputBoolean: + case VirtualTerminalObjectType::InputString: + case VirtualTerminalObjectType::InputNumber: + case VirtualTerminalObjectType::InputList: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::AuxiliaryFunctionType2: + case VirtualTerminalObjectType::AuxiliaryInputType2: + case VirtualTerminalObjectType::AuxiliaryControlDesignatorType2: + case VirtualTerminalObjectType::Macro: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool Container::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + // All attributes are read only + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool Container::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::Hidden): + { + returnedAttributeData = get_hidden(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool Container::get_hidden() const + { + return hidden; + } + + void Container::set_hidden(bool value) + { + hidden = value; + } + + VirtualTerminalObjectType SoftKeyMask::get_object_type() const + { + return VirtualTerminalObjectType::SoftKeyMask; + } + + std::uint32_t SoftKeyMask::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool SoftKeyMask::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::Key: + case VirtualTerminalObjectType::Macro: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool SoftKeyMask::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool SoftKeyMask::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + VirtualTerminalObjectType Key::get_object_type() const + { + return VirtualTerminalObjectType::Key; + } + + std::uint32_t Key::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool Key::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::Macro: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool Key::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::KeyCode: + { + set_key_code(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool Key::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::KeyCode): + { + returnedAttributeData = get_key_code(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint8_t Key::get_key_code() const + { + return keyCode; + } + + void Key::set_key_code(std::uint8_t value) + { + keyCode = value; + } + + VirtualTerminalObjectType KeyGroup::get_object_type() const + { + return VirtualTerminalObjectType::KeyGroup; + } + + std::uint32_t KeyGroup::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool KeyGroup::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + if (NULL_OBJECT_ID != get_name_object_id()) + { + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::Key: + case VirtualTerminalObjectType::Macro: + { + // Key and macro are always valid + } + break; + + case VirtualTerminalObjectType::ObjectPointer: + { + auto objectPointer = std::static_pointer_cast(childObject); + + if (NULL_OBJECT_ID != objectPointer->get_value()) + { + if ((nullptr != get_object_by_id(objectPointer->get_value(), objectPool)) && + (VirtualTerminalObjectType::Key == get_object_by_id(objectPointer->get_value(), objectPool)->get_object_type())) + { + // Valid Child Object + } + else + { + anyWrongChildType = true; + } + } + else + { + // If there's no children, then it's valid + } + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + + if (!validate_name(nameID, objectPool)) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool KeyGroup::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Name: + { + returnedError = AttributeError::InvalidValue; + + if (objectPool.find(objectID) != objectPool.end()) + { + auto newName = static_cast(rawAttributeData); + auto newNameObject = objectPool.at(newName); + + if (validate_name(newName, objectPool)) + { + nameID = newName; + retVal = true; + } + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool KeyGroup::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::Name): + { + returnedAttributeData = get_name_object_id(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint16_t KeyGroup::get_key_group_icon() const + { + return keyGroupIcon; + } + + void KeyGroup::set_key_group_icon(std::uint16_t value) + { + keyGroupIcon = value; + } + + bool KeyGroup::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void KeyGroup::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void KeyGroup::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint16_t KeyGroup::get_name_object_id() const + { + return nameID; + } + + void KeyGroup::set_name_object_id(std::uint16_t value) + { + // This value cannot be NULL_OBJECT_ID after it has been set! + if (NULL_OBJECT_ID != value) + { + nameID = value; + } + } + + bool KeyGroup::validate_name(std::uint16_t nameIDToValidate, const std::map> &objectPool) const + { + auto newNameObject = objectPool.at(nameIDToValidate); + bool retVal = false; + + if ((NULL_OBJECT_ID != nameIDToValidate) && + (nullptr != newNameObject) && + ((VirtualTerminalObjectType::OutputString == newNameObject->get_object_type()) || + (VirtualTerminalObjectType::ObjectPointer == newNameObject->get_object_type()))) + { + if (VirtualTerminalObjectType::ObjectPointer == newNameObject->get_object_type()) + { + if (newNameObject->get_number_children() > 0) + { + auto label = objectPool.at(std::static_pointer_cast(newNameObject)->get_child_id(0)); + + if ((nullptr != label) && + (VirtualTerminalObjectType::OutputString == label->get_object_type())) + { + retVal = true; + } + } + } + else + { + retVal = true; + } + } + return retVal; + } + + VirtualTerminalObjectType Button::get_object_type() const + { + return VirtualTerminalObjectType::Button; + } + + std::uint32_t Button::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool Button::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::Macro: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool Button::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BorderColour: + { + set_border_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::KeyCode: + { + set_key_code(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool Button::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::BorderColour): + { + returnedAttributeData = get_border_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::KeyCode): + { + returnedAttributeData = get_key_code(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint8_t Button::get_key_code() const + { + return keyCode; + } + + void Button::set_key_code(std::uint8_t value) + { + keyCode = value; + } + + std::uint8_t Button::get_border_colour() const + { + return borderColour; + } + + void Button::set_border_colour(std::uint8_t value) + { + borderColour = value; + } + + bool Button::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void Button::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void Button::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + VirtualTerminalObjectType InputBoolean::get_object_type() const + { + return VirtualTerminalObjectType::InputBoolean; + } + + std::uint32_t InputBoolean::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool InputBoolean::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableReference = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableReference) + { + if (VirtualTerminalObjectType::NumberVariable != variableReference->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify that the foreground colour is a font attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_foreground_colour_object_id()) + { + auto foregroundColour = get_object_by_id(get_foreground_colour_object_id(), objectPool); + + if (nullptr != foregroundColour) + { + if (VirtualTerminalObjectType::FontAttributes != foregroundColour->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool InputBoolean::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::ForegroundColour: + { + returnedError = AttributeError::AnyOtherError; + + if (NULL_OBJECT_ID == rawAttributeData) + { + set_foreground_colour_object_id(static_cast(rawAttributeData)); + retVal = true; + } + else if (objectPool.find(static_cast(rawAttributeData)) != objectPool.end()) + { + if (nullptr != objectPool.at(static_cast(rawAttributeData)) && + (VirtualTerminalObjectType::FontAttributes == objectPool.at(static_cast(rawAttributeData))->get_object_type())) + { + set_foreground_colour_object_id(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + } + break; + + case AttributeName::VariableReference: + { + returnedError = AttributeError::AnyOtherError; + + if (NULL_OBJECT_ID == rawAttributeData) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else if (objectPool.find(static_cast(rawAttributeData)) != objectPool.end()) + { + if (nullptr != objectPool.at(static_cast(rawAttributeData)) && + (VirtualTerminalObjectType::NumberVariable == objectPool.at(static_cast(rawAttributeData))->get_object_type())) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + } + break; + + case AttributeName::Value: + { + set_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Enabled: + { + set_enabled(0 != rawAttributeData); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool InputBoolean::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::ForegroundColour): + { + returnedAttributeData = get_foreground_colour_object_id(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::Enabled): + { + returnedAttributeData = get_enabled(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint8_t InputBoolean::get_value() const + { + return value; + } + + void InputBoolean::set_value(std::uint8_t inputValue) + { + value = inputValue; + } + + bool InputBoolean::get_enabled() const + { + return enabled; + } + + void InputBoolean::set_enabled(bool isEnabled) + { + enabled = isEnabled; + } + + std::uint16_t InputBoolean::get_foreground_colour_object_id() const + { + return foregroundColourObjectID; + } + + void InputBoolean::set_foreground_colour_object_id(std::uint16_t fontAttributeValue) + { + foregroundColourObjectID = fontAttributeValue; + } + + std::uint16_t InputBoolean::get_variable_reference() const + { + return variableReference; + } + + void InputBoolean::set_variable_reference(std::uint16_t numberVariableValue) + { + variableReference = numberVariableValue; + } + + VirtualTerminalObjectType InputString::get_object_type() const + { + return VirtualTerminalObjectType::InputString; + } + + std::uint32_t InputString::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool InputString::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto objectToCheck = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != objectToCheck) + { + if (VirtualTerminalObjectType::StringVariable != objectToCheck->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + if (NULL_OBJECT_ID != get_input_attributes()) + { + auto objectToCheck = get_object_by_id(get_input_attributes(), objectPool); + + if (nullptr != objectToCheck) + { + if (VirtualTerminalObjectType::InputAttributes != objectToCheck->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + if (NULL_OBJECT_ID != get_font_attributes()) + { + auto objectToCheck = get_object_by_id(get_font_attributes(), objectPool); + + if (nullptr != objectToCheck) + { + if (VirtualTerminalObjectType::FontAttributes != objectToCheck->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool InputString::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontAttributes: + { + auto fontAttributesObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fontAttributesObject) && + (VirtualTerminalObjectType::FontAttributes == fontAttributesObject->get_object_type()))) + { + set_font_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::InputAttributes: + { + auto inputAttributesObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != inputAttributesObject) && + (VirtualTerminalObjectType::InputAttributes == inputAttributesObject->get_object_type()))) + { + set_input_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableReferenceObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableReferenceObject) && + (VirtualTerminalObjectType::StringVariable == variableReferenceObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Justification: + { + set_justification_bitfield(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Enabled: + { + set_enabled(0 != rawAttributeData); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool InputString::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::FontAttributes): + { + returnedAttributeData = get_font_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::InputAttributes): + { + returnedAttributeData = get_input_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Justification): + { + returnedAttributeData = justificationBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::Enabled): + { + returnedAttributeData = get_enabled(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool InputString::get_enabled() const + { + return enabled; + } + + void InputString::set_enabled(bool value) + { + enabled = value; + } + + bool InputString::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void InputString::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void InputString::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + InputString::HorizontalJustification InputString::get_horizontal_justification() const + { + return static_cast(justificationBitfield & 0x03); + } + + InputString::VerticalJustification InputString::get_vertical_justification() const + { + return static_cast((justificationBitfield >> 2) & 0x03); + } + + void InputString::set_justification_bitfield(std::uint8_t value) + { + justificationBitfield = value; + } + + std::string InputString::get_value() const + { + return stringValue; + } + + void InputString::set_value(const std::string &value) + { + stringValue = value; + } + + std::uint16_t InputString::get_font_attributes() const + { + return fontAttributes; + } + + void InputString::set_font_attributes(std::uint16_t fontAttributesValue) + { + fontAttributes = fontAttributesValue; + } + + std::uint16_t InputString::get_variable_reference() const + { + return variableReference; + } + + void InputString::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + std::uint16_t InputString::get_input_attributes() const + { + return inputAttributes; + } + + void InputString::set_input_attributes(std::uint16_t inputAttributesValue) + { + inputAttributes = inputAttributesValue; + } + + VirtualTerminalObjectType InputNumber::get_object_type() const + { + return VirtualTerminalObjectType::InputNumber; + } + + std::uint32_t InputNumber::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool InputNumber::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableReference = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableReference) + { + if (VirtualTerminalObjectType::NumberVariable != variableReference->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify that the font attributes is a font attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_font_attributes()) + { + auto fontAttributes = get_object_by_id(get_font_attributes(), objectPool); + + if (nullptr != fontAttributes) + { + if (VirtualTerminalObjectType::FontAttributes != fontAttributes->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool InputNumber::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontAttributes: + { + auto fontAttributesObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fontAttributesObject) && + (VirtualTerminalObjectType::FontAttributes == fontAttributesObject->get_object_type()))) + { + set_font_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::MinValue: + { + set_minimum_value(rawAttributeData); + retVal = true; + } + break; + + case AttributeName::MaxValue: + { + set_maximum_value(rawAttributeData); + retVal = true; + } + break; + + case AttributeName::Offset: + { + auto temp = reinterpret_cast(&rawAttributeData); + set_offset(*temp); + retVal = true; + } + break; + + case AttributeName::Scale: + { + auto temp = reinterpret_cast(&rawAttributeData); + set_scale(*temp); + retVal = true; + } + break; + + case AttributeName::NumberOfDecimals: + { + set_number_of_decimals(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Format: + { + set_format(0 != rawAttributeData); + retVal = true; + } + break; + + case AttributeName::Justification: + { + set_justification_bitfield(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool InputNumber::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::FontAttributes): + { + returnedAttributeData = get_font_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = options; + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::MinValue): + { + returnedAttributeData = get_minimum_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::MaxValue): + { + returnedAttributeData = get_maximum_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::Offset): + { + auto temp = reinterpret_cast(&offset); + returnedAttributeData = *temp; + retVal = true; + } + break; + + case static_cast(AttributeName::Scale): + { + auto temp = reinterpret_cast(&scale); + returnedAttributeData = *temp; + retVal = true; + } + break; + + case static_cast(AttributeName::NumberOfDecimals): + { + returnedAttributeData = get_number_of_decimals(); + retVal = true; + } + break; + + case static_cast(AttributeName::Format): + { + returnedAttributeData = get_format(); + retVal = true; + } + break; + + case static_cast(AttributeName::Justification): + { + returnedAttributeData = justificationBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = value; + retVal = true; + } + break; + + case static_cast(AttributeName::Options2): + { + returnedAttributeData = options2; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + InputNumber::HorizontalJustification InputNumber::get_horizontal_justification() const + { + return static_cast(justificationBitfield & 0x03); + } + + InputNumber::VerticalJustification InputNumber::get_vertical_justification() const + { + return static_cast((justificationBitfield >> 2) & 0x03); + } + + void InputNumber::set_justification_bitfield(std::uint8_t newJustification) + { + justificationBitfield = newJustification; + } + + float InputNumber::get_scale() const + { + return scale; + } + + void InputNumber::set_scale(float newScale) + { + scale = newScale; + } + + std::uint32_t InputNumber::get_maximum_value() const + { + return maximumValue; + } + + void InputNumber::set_maximum_value(std::uint32_t newMax) + { + maximumValue = newMax; + } + + std::uint32_t InputNumber::get_minimum_value() const + { + return minimumValue; + } + + void InputNumber::set_minimum_value(std::uint32_t newMin) + { + minimumValue = newMin; + } + + std::int32_t InputNumber::get_offset() const + { + return offset; + } + + void InputNumber::set_offset(std::int32_t newOffset) + { + offset = newOffset; + } + + std::uint8_t InputNumber::get_number_of_decimals() const + { + return numberOfDecimals; + } + + void InputNumber::set_number_of_decimals(std::uint8_t numDecimals) + { + numberOfDecimals = numDecimals; + } + + bool InputNumber::get_format() const + { + return format; + } + + void InputNumber::set_format(bool newFormat) + { + format = newFormat; + } + + bool InputNumber::get_option(Options newOption) const + { + return (0 != ((1 << static_cast(newOption)) & options)); + } + + void InputNumber::set_options(std::uint8_t newOptions) + { + options = newOptions; + } + + void InputNumber::set_option(Options option, bool optionValue) + { + if (optionValue) + { + options |= (1 << static_cast(option)); + } + else + { + options &= ~(1 << static_cast(option)); + } + } + + bool InputNumber::get_option2(Options2 newOption) const + { + return (0 != ((1 << static_cast(newOption)) & options2)); + } + + void InputNumber::set_options2(std::uint8_t newOptions) + { + options2 = newOptions; + } + + void InputNumber::set_option2(Options2 option, bool newOption) + { + if (newOption) + { + options2 |= (1 << static_cast(option)); + } + else + { + options2 &= ~(1 << static_cast(option)); + } + } + + std::uint32_t InputNumber::get_value() const + { + return value; + } + + void InputNumber::set_value(std::uint32_t inputValue) + { + value = inputValue; + } + + std::uint16_t InputNumber::get_font_attributes() const + { + return fontAttributes; + } + + void InputNumber::set_font_attributes(std::uint16_t fontAttributesValue) + { + fontAttributes = fontAttributesValue; + } + + std::uint16_t InputNumber::get_variable_reference() const + { + return variableReference; + } + + void InputNumber::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + VirtualTerminalObjectType InputList::get_object_type() const + { + return VirtualTerminalObjectType::InputList; + } + + std::uint32_t InputList::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool InputList::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ScaledGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool InputList::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Value: + { + set_value(rawAttributeData); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool InputList::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool InputList::get_option(Options option) const + { + return (0 != (optionsBitfield & (1 << static_cast(option)))); + } + + void InputList::set_options(std::uint8_t options) + { + optionsBitfield = options; + } + + void InputList::set_option(Options option, bool optionValue) + { + if (optionValue) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint8_t InputList::get_value() const + { + return value; + } + + void InputList::set_value(std::uint8_t inputValue) + { + value = inputValue; + } + + bool InputList::change_list_item(std::uint8_t index, std::uint16_t newListItem, const std::map> &objectPool) + { + bool retVal = false; + + if ((index < children.size()) && + ((NULL_OBJECT_ID == newListItem) || + (nullptr != get_object_by_id(newListItem, objectPool)))) + { + if (nullptr != get_object_by_id(newListItem, objectPool)) + { + switch (get_object_by_id(newListItem, objectPool)->get_object_type()) + { + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ScaledGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + { + children.at(index).id = newListItem; + retVal = true; + } + break; + + default: + { + // Invalid child object type + } + break; + } + } + else + { + children.at(index).id = newListItem; + retVal = true; + } + } + return retVal; + } + + void InputList::set_variable_reference(std::uint16_t referencedObjectID) + { + variableReference = referencedObjectID; + } + + std::uint16_t InputList::get_variable_reference() const + { + return variableReference; + } + + std::uint8_t InputList::get_number_of_list_items() const + { + return numberOfListItems; + } + + void InputList::set_number_of_list_items(std::uint8_t value) + { + numberOfListItems = value; + } + + VirtualTerminalObjectType OutputString::get_object_type() const + { + return VirtualTerminalObjectType::OutputString; + } + + std::uint32_t OutputString::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputString::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableReference = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableReference) + { + if (VirtualTerminalObjectType::StringVariable != variableReference->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify that the font attributes is a font attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_font_attributes()) + { + auto fontAttributes = get_object_by_id(get_font_attributes(), objectPool); + + if (nullptr != fontAttributes) + { + if (VirtualTerminalObjectType::FontAttributes != fontAttributes->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputString::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontAttributes: + { + auto fontAttributesObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fontAttributesObject) && + (VirtualTerminalObjectType::FontAttributes == fontAttributesObject->get_object_type()))) + { + set_font_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::StringVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Justification: + { + set_justification_bitfield(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputString::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::FontAttributes): + { + returnedAttributeData = get_font_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Justification): + { + returnedAttributeData = justificationBitfield; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool OutputString::get_option(Options option) const + { + return (0 != (optionsBitfield & (1 << static_cast(option)))); + } + + void OutputString::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void OutputString::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + OutputString::HorizontalJustification OutputString::get_horizontal_justification() const + { + return static_cast(justificationBitfield & 0x03); + } + + OutputString::VerticalJustification OutputString::get_vertical_justification() const + { + return static_cast((justificationBitfield >> 2) & 0x03); + } + + void OutputString::set_justification_bitfield(std::uint8_t value) + { + justificationBitfield = value; + } + + std::string OutputString::get_value() const + { + return stringValue; + } + + void OutputString::set_value(const std::string &value) + { + stringValue = value; + } + + std::uint16_t OutputString::get_font_attributes() const + { + return fontAttributes; + } + + void OutputString::set_font_attributes(std::uint16_t fontAttributesValue) + { + fontAttributes = fontAttributesValue; + } + + std::uint16_t OutputString::get_variable_reference() const + { + return variableReference; + } + + void OutputString::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + VirtualTerminalObjectType OutputNumber::get_object_type() const + { + return VirtualTerminalObjectType::OutputNumber; + } + + std::uint32_t OutputNumber::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputNumber::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableReference = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableReference) + { + if (VirtualTerminalObjectType::NumberVariable != variableReference->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify that the font attributes is a font attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_font_attributes()) + { + auto fontAttributes = get_object_by_id(get_font_attributes(), objectPool); + + if (nullptr != fontAttributes) + { + if (VirtualTerminalObjectType::FontAttributes != fontAttributes->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputNumber::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontAttributes: + { + auto fontAttributesObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fontAttributesObject) && + (VirtualTerminalObjectType::FontAttributes == fontAttributesObject->get_object_type()))) + { + set_font_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Offset: + { + auto temp = reinterpret_cast(&rawAttributeData); + set_offset(*temp); + retVal = true; + } + break; + + case AttributeName::Scale: + { + auto temp = reinterpret_cast(&rawAttributeData); + set_scale(*temp); + retVal = true; + } + break; + + case AttributeName::NumberOfDecimals: + { + set_number_of_decimals(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Format: + { + set_format(0 != rawAttributeData); + retVal = true; + } + break; + + case AttributeName::Justification: + { + set_justification_bitfield(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputNumber::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + case static_cast(AttributeName::FontAttributes): + { + returnedAttributeData = get_font_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Offset): + { + auto temp = reinterpret_cast(&offset); + returnedAttributeData = *temp; + retVal = true; + } + break; + + case static_cast(AttributeName::Scale): + { + auto temp = reinterpret_cast(&scale); + returnedAttributeData = *temp; + retVal = true; + } + break; + + case static_cast(AttributeName::NumberOfDecimals): + { + returnedAttributeData = get_number_of_decimals(); + retVal = true; + } + break; + + case static_cast(AttributeName::Format): + { + returnedAttributeData = get_format(); + retVal = true; + } + break; + + case static_cast(AttributeName::Justification): + { + returnedAttributeData = justificationBitfield; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + bool OutputNumber::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void OutputNumber::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void OutputNumber::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + OutputNumber::HorizontalJustification OutputNumber::get_horizontal_justification() const + { + return static_cast(justificationBitfield & 0x03); + } + + OutputNumber::VerticalJustification OutputNumber::get_vertical_justification() const + { + return static_cast((justificationBitfield >> 2) & 0x03); + } + + void OutputNumber::set_justification_bitfield(std::uint8_t value) + { + justificationBitfield = value; + } + + float OutputNumber::get_scale() const + { + return scale; + } + + void OutputNumber::set_scale(float scaleValue) + { + scale = scaleValue; + } + + std::int32_t OutputNumber::get_offset() const + { + return offset; + } + + void OutputNumber::set_offset(std::int32_t offsetValue) + { + offset = offsetValue; + } + + std::uint8_t OutputNumber::get_number_of_decimals() const + { + return numberOfDecimals; + } + + void OutputNumber::set_number_of_decimals(std::uint8_t decimalValue) + { + numberOfDecimals = decimalValue; + } + + bool OutputNumber::get_format() const + { + return format; + } + + void OutputNumber::set_format(bool shouldFormatAsExponential) + { + format = shouldFormatAsExponential; + } + + std::uint32_t OutputNumber::get_value() const + { + return value; + } + + void OutputNumber::set_value(std::uint32_t inputValue) + { + value = inputValue; + } + + void OutputNumber::set_variable_reference(std::uint16_t referencedObjectID) + { + variableReference = referencedObjectID; + } + + std::uint16_t OutputNumber::get_variable_reference() const + { + return variableReference; + } + + std::uint16_t OutputNumber::get_font_attributes() const + { + return fontAttributes; + } + + void OutputNumber::set_font_attributes(std::uint16_t fontAttributesValue) + { + fontAttributes = fontAttributesValue; + } + + VirtualTerminalObjectType OutputList::get_object_type() const + { + return VirtualTerminalObjectType::OutputList; + } + + std::uint32_t OutputList::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputList::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableReference = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableReference) + { + if (VirtualTerminalObjectType::NumberVariable != variableReference->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::Macro: + case VirtualTerminalObjectType::WorkingSet: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::Button: + case VirtualTerminalObjectType::KeyGroup: + case VirtualTerminalObjectType::InputBoolean: + case VirtualTerminalObjectType::InputString: + case VirtualTerminalObjectType::InputNumber: + case VirtualTerminalObjectType::InputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::Animation: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ScaledGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ExternalObjectPointer: + case VirtualTerminalObjectType::AuxiliaryFunctionType2: + case VirtualTerminalObjectType::AuxiliaryInputType2: + case VirtualTerminalObjectType::AuxiliaryControlDesignatorType2: + { + // Valid Child Object + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + } + return ((!anyWrongChildType) && + (NULL_OBJECT_ID != objectID)); + } + + bool OutputList::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Value: + { + set_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputList::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint8_t OutputList::get_number_of_list_items() const + { + return numberOfListItems; + } + + void OutputList::set_number_of_list_items(std::uint8_t value) + { + numberOfListItems = value; + } + + std::uint8_t OutputList::get_value() const + { + return value; + } + + void OutputList::set_value(std::uint8_t aValue) + { + value = aValue; + } + + bool OutputList::change_list_item(std::uint8_t index, std::uint16_t newListItem, const std::map> &objectPool) + { + bool retVal = false; + + if ((index < children.size()) && + ((NULL_OBJECT_ID == newListItem) || + ((nullptr != get_object_by_id(newListItem, objectPool)) && + (VirtualTerminalObjectType::NumberVariable == get_object_by_id(newListItem, objectPool)->get_object_type())))) + { + children.at(index).id = newListItem; + retVal = true; + } + return retVal; + } + + void OutputList::set_variable_reference(std::uint16_t referencedObjectID) + { + variableReference = referencedObjectID; + } + + std::uint16_t OutputList::get_variable_reference() const + { + return variableReference; + } + + VirtualTerminalObjectType OutputLine::get_object_type() const + { + return VirtualTerminalObjectType::OutputLine; + } + + bool OutputLine::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the line attributes is a line attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_line_attributes()) + { + auto lineAttributesObject = get_object_by_id(get_line_attributes(), objectPool); + + if (nullptr != lineAttributesObject) + { + if (VirtualTerminalObjectType::LineAttributes != lineAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputLine::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::LineAttributes: + { + auto lineAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != lineAttributeObject) && + (VirtualTerminalObjectType::LineAttributes == lineAttributeObject->get_object_type()))) + { + set_line_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::LineDirection: + { + if (rawAttributeData <= static_cast(LineDirection::BottomLeftToTopRight)) + { + set_line_direction(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputLine::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineAttributes): + { + returnedAttributeData = get_line_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineDirection): + { + returnedAttributeData = lineDirection; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint32_t OutputLine::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + OutputLine::LineDirection OutputLine::get_line_direction() const + { + return static_cast(lineDirection); + } + + void OutputLine::set_line_direction(LineDirection value) + { + lineDirection = static_cast(value); + } + + std::uint16_t OutputLine::get_line_attributes() const + { + return lineAttributes; + } + + void OutputLine::set_line_attributes(std::uint16_t lineAttributesObject) + { + lineAttributes = lineAttributesObject; + } + + VirtualTerminalObjectType OutputRectangle::get_object_type() const + { + return VirtualTerminalObjectType::OutputRectangle; + } + + std::uint32_t OutputRectangle::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputRectangle::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the line attributes is a line attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_line_attributes()) + { + auto lineAttributesObject = get_object_by_id(get_line_attributes(), objectPool); + + if (nullptr != lineAttributesObject) + { + if (VirtualTerminalObjectType::LineAttributes != lineAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify the fill attributes is a fill attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_fill_attributes()) + { + auto fillAttributesObject = get_object_by_id(get_fill_attributes(), objectPool); + + if (nullptr != fillAttributesObject) + { + if (VirtualTerminalObjectType::FillAttributes != fillAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputRectangle::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::LineAttributes: + { + auto lineAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != lineAttributeObject) && + (VirtualTerminalObjectType::LineAttributes == lineAttributeObject->get_object_type()))) + { + set_line_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::LineSuppression: + { + set_line_suppression_bitfield(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FillAttributes: + { + auto fillAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fillAttributeObject) && + (VirtualTerminalObjectType::FillAttributes == fillAttributeObject->get_object_type()))) + { + set_fill_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputRectangle::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineAttributes): + { + returnedAttributeData = get_line_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineSuppression): + { + returnedAttributeData = lineSuppressionBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::FillAttributes): + { + returnedAttributeData = get_fill_attributes(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint8_t OutputRectangle::get_line_suppression_bitfield() const + { + return lineSuppressionBitfield; + } + + void OutputRectangle::set_line_suppression_bitfield(std::uint8_t value) + { + lineSuppressionBitfield = value; + } + + std::uint16_t OutputRectangle::get_line_attributes() const + { + return lineAttributes; + } + + void OutputRectangle::set_line_attributes(std::uint16_t lineAttributesObject) + { + lineAttributes = lineAttributesObject; + } + + std::uint16_t OutputRectangle::get_fill_attributes() const + { + return fillAttributes; + } + + void OutputRectangle::set_fill_attributes(std::uint16_t fillAttributesObject) + { + fillAttributes = fillAttributesObject; + } + + VirtualTerminalObjectType OutputEllipse::get_object_type() const + { + return VirtualTerminalObjectType::OutputEllipse; + } + + std::uint32_t OutputEllipse::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputEllipse::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the line attributes is a line attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_line_attributes()) + { + auto lineAttributesObject = get_object_by_id(get_line_attributes(), objectPool); + + if (nullptr != lineAttributesObject) + { + if (VirtualTerminalObjectType::LineAttributes != lineAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify the fill attributes is a fill attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_fill_attributes()) + { + auto fillAttributesObject = get_object_by_id(get_fill_attributes(), objectPool); + + if (nullptr != fillAttributesObject) + { + if (VirtualTerminalObjectType::FillAttributes != fillAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputEllipse::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::LineAttributes: + { + auto lineAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != lineAttributeObject) && + (VirtualTerminalObjectType::LineAttributes == lineAttributeObject->get_object_type()))) + { + set_line_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::EllipseType: + { + if (rawAttributeData <= static_cast(EllipseType::ClosedEllipseSection)) + { + set_ellipse_type(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + case AttributeName::StartAngle: + { + set_start_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::EndAngle: + { + set_end_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FillAttributes: + { + auto fillAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fillAttributeObject) && + (VirtualTerminalObjectType::FillAttributes == fillAttributeObject->get_object_type()))) + { + set_fill_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputEllipse::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineAttributes): + { + returnedAttributeData = get_line_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::EllipseType): + { + returnedAttributeData = ellipseType; + retVal = true; + } + break; + + case static_cast(AttributeName::StartAngle): + { + returnedAttributeData = startAngle; + retVal = true; + } + break; + + case static_cast(AttributeName::EndAngle): + { + returnedAttributeData = endAngle; + retVal = true; + } + break; + + case static_cast(AttributeName::FillAttributes): + { + returnedAttributeData = get_fill_attributes(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + OutputEllipse::EllipseType OutputEllipse::get_ellipse_type() const + { + return static_cast(ellipseType); + } + + void OutputEllipse::set_ellipse_type(EllipseType value) + { + ellipseType = static_cast(value); + } + + std::uint8_t OutputEllipse::get_start_angle() const + { + return startAngle; + } + + void OutputEllipse::set_start_angle(std::uint8_t value) + { + startAngle = value; + } + + std::uint8_t OutputEllipse::get_end_angle() const + { + return endAngle; + } + + void OutputEllipse::set_end_angle(std::uint8_t value) + { + endAngle = value; + } + + std::uint16_t OutputEllipse::get_line_attributes() const + { + return lineAttributes; + } + + void OutputEllipse::set_line_attributes(std::uint16_t lineAttributesObject) + { + lineAttributes = lineAttributesObject; + } + + std::uint16_t OutputEllipse::get_fill_attributes() const + { + return fillAttributes; + } + + void OutputEllipse::set_fill_attributes(std::uint16_t fillAttributesObject) + { + fillAttributes = fillAttributesObject; + } + + VirtualTerminalObjectType OutputPolygon::get_object_type() const + { + return VirtualTerminalObjectType::OutputPolygon; + } + + std::uint32_t OutputPolygon::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputPolygon::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the line attributes is a line attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_line_attributes()) + { + auto lineAttributesObject = get_object_by_id(get_line_attributes(), objectPool); + + if (nullptr != lineAttributesObject) + { + if (VirtualTerminalObjectType::LineAttributes != lineAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify the fill attributes is a fill attribute or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_fill_attributes()) + { + auto fillAttributesObject = get_object_by_id(get_fill_attributes(), objectPool); + + if (nullptr != fillAttributesObject) + { + if (VirtualTerminalObjectType::FillAttributes != fillAttributesObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputPolygon::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::LineAttributes: + { + auto lineAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != lineAttributeObject) && + (VirtualTerminalObjectType::LineAttributes == lineAttributeObject->get_object_type()))) + { + set_line_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::FillAttributes: + { + auto fillAttributeObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != fillAttributeObject) && + (VirtualTerminalObjectType::FillAttributes == fillAttributeObject->get_object_type()))) + { + set_fill_attributes(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::PolygonType: + { + if (rawAttributeData <= static_cast(PolygonType::Open)) + { + set_type(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputPolygon::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::LineAttributes): + { + returnedAttributeData = get_line_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::FillAttributes): + { + returnedAttributeData = get_fill_attributes(); + retVal = true; + } + break; + + case static_cast(AttributeName::PolygonType): + { + returnedAttributeData = polygonType; + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + void OutputPolygon::add_point(std::uint16_t x, std::uint16_t y) + { + pointList.push_back({ x, y }); + } + + std::uint8_t OutputPolygon::get_number_of_points() const + { + return static_cast(pointList.size()); + } + + OutputPolygon::PolygonPoint OutputPolygon::get_point(std::uint8_t index) + { + PolygonPoint retVal = { 0, 0 }; + + if (index < pointList.size()) + { + retVal = pointList[index]; + } + return retVal; + } + + OutputPolygon::PolygonType OutputPolygon::get_type() const + { + return static_cast(polygonType); + } + + void OutputPolygon::set_type(PolygonType value) + { + polygonType = static_cast(value); + } + + std::uint16_t OutputPolygon::get_line_attributes() const + { + return lineAttributes; + } + + void OutputPolygon::set_line_attributes(std::uint16_t lineAttributesObject) + { + lineAttributes = lineAttributesObject; + } + + std::uint16_t OutputPolygon::get_fill_attributes() const + { + return fillAttributes; + } + + void OutputPolygon::set_fill_attributes(std::uint16_t fillAttributesObject) + { + fillAttributes = fillAttributesObject; + } + + VirtualTerminalObjectType OutputMeter::get_object_type() const + { + return VirtualTerminalObjectType::OutputMeter; + } + + std::uint32_t OutputMeter::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputMeter::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableObject = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableObject) + { + if (VirtualTerminalObjectType::NumberVariable != variableObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputMeter::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::NeedleColour: + { + set_needle_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BorderColour: + { + set_border_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::ArcAndTickColour: + { + set_arc_and_tick_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::NumberOfTicks: + { + set_number_of_ticks(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::StartAngle: + { + set_start_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::EndAngle: + { + set_end_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MinValue: + { + set_min_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MaxValue: + { + set_max_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::Value: + { + set_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputMeter::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::NeedleColour): + { + returnedAttributeData = get_needle_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::BorderColour): + { + returnedAttributeData = get_border_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::ArcAndTickColour): + { + returnedAttributeData = get_arc_and_tick_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::NumberOfTicks): + { + returnedAttributeData = get_number_of_ticks(); + retVal = true; + } + break; + + case static_cast(AttributeName::StartAngle): + { + returnedAttributeData = get_start_angle(); + retVal = true; + } + break; + + case static_cast(AttributeName::EndAngle): + { + returnedAttributeData = get_end_angle(); + retVal = true; + } + break; + + case static_cast(AttributeName::MinValue): + { + returnedAttributeData = get_min_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::MaxValue): + { + returnedAttributeData = get_max_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint16_t OutputMeter::get_min_value() const + { + return minValue; + } + + void OutputMeter::set_min_value(std::uint16_t value) + { + minValue = value; + } + + std::uint16_t OutputMeter::get_max_value() const + { + return maxValue; + } + + void OutputMeter::set_max_value(std::uint16_t value) + { + maxValue = value; + } + + std::uint16_t OutputMeter::get_value() const + { + return value; + } + + void OutputMeter::set_value(std::uint16_t aValue) + { + value = aValue; + } + + std::uint8_t OutputMeter::get_needle_colour() const + { + return needleColour; + } + + void OutputMeter::set_needle_colour(std::uint8_t colourIndex) + { + needleColour = colourIndex; + } + + std::uint8_t OutputMeter::get_border_colour() const + { + return borderColour; + } + + void OutputMeter::set_border_colour(std::uint8_t colourIndex) + { + borderColour = colourIndex; + } + + std::uint8_t OutputMeter::get_arc_and_tick_colour() const + { + return arcAndTickColour; + } + + void OutputMeter::set_arc_and_tick_colour(std::uint8_t colourIndex) + { + arcAndTickColour = colourIndex; + } + + std::uint8_t OutputMeter::get_number_of_ticks() const + { + return numberOfTicks; + } + + void OutputMeter::set_number_of_ticks(std::uint8_t ticks) + { + numberOfTicks = ticks; + } + + bool OutputMeter::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void OutputMeter::set_options(std::uint8_t options) + { + optionsBitfield = options; + } + + void OutputMeter::set_option(Options option, bool optionValue) + { + if (optionValue) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint8_t OutputMeter::get_start_angle() const + { + return startAngle; + } + + void OutputMeter::set_start_angle(std::uint8_t value) + { + startAngle = value; + } + + std::uint8_t OutputMeter::get_end_angle() const + { + return endAngle; + } + + void OutputMeter::set_end_angle(std::uint8_t value) + { + endAngle = value; + } + + std::uint16_t OutputMeter::get_variable_reference() const + { + return variableReference; + } + + void OutputMeter::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + VirtualTerminalObjectType OutputLinearBarGraph::get_object_type() const + { + return VirtualTerminalObjectType::OutputLinearBarGraph; + } + + std::uint32_t OutputLinearBarGraph::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputLinearBarGraph::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableObject = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableObject) + { + if (VirtualTerminalObjectType::NumberVariable != variableObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify the target value variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_target_value_reference()) + { + auto variableObject = get_object_by_id(get_target_value_reference(), objectPool); + + if (nullptr != variableObject) + { + if (VirtualTerminalObjectType::NumberVariable != variableObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputLinearBarGraph::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Colour: + { + set_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::TargetLineColour: + { + set_target_line_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::NumberOfTicks: + { + set_number_of_ticks(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MinValue: + { + set_min_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MaxValue: + { + set_max_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::TargetValueVariableReference: + { + set_target_value_reference(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::TargetValue: + { + set_target_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Value: + { + set_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputLinearBarGraph::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::Colour): + { + returnedAttributeData = get_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetLineColour): + { + returnedAttributeData = get_target_line_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::NumberOfTicks): + { + returnedAttributeData = get_number_of_ticks(); + retVal = true; + } + break; + + case static_cast(AttributeName::MinValue): + { + returnedAttributeData = get_min_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::MaxValue): + { + returnedAttributeData = get_max_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetValueVariableReference): + { + returnedAttributeData = get_target_value_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetValue): + { + returnedAttributeData = get_target_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint16_t OutputLinearBarGraph::get_min_value() const + { + return minValue; + } + + void OutputLinearBarGraph::set_min_value(std::uint16_t value) + { + minValue = value; + } + + std::uint16_t OutputLinearBarGraph::get_max_value() const + { + return maxValue; + } + + void OutputLinearBarGraph::set_max_value(std::uint16_t value) + { + maxValue = value; + } + + std::uint16_t OutputLinearBarGraph::get_value() const + { + return value; + } + + void OutputLinearBarGraph::set_value(std::uint16_t aValue) + { + value = aValue; + } + + std::uint16_t OutputLinearBarGraph::get_target_value() const + { + return targetValue; + } + + void OutputLinearBarGraph::set_target_value(std::uint16_t valueTarget) + { + targetValue = valueTarget; + } + + std::uint16_t OutputLinearBarGraph::get_target_value_reference() const + { + return targetValueReference; + } + + void OutputLinearBarGraph::set_target_value_reference(std::uint16_t valueReferenceObjectID) + { + targetValueReference = valueReferenceObjectID; + } + + std::uint8_t OutputLinearBarGraph::get_number_of_ticks() const + { + return numberOfTicks; + } + + void OutputLinearBarGraph::set_number_of_ticks(std::uint8_t value) + { + numberOfTicks = value; + } + + std::uint8_t OutputLinearBarGraph::get_colour() const + { + return colour; + } + + void OutputLinearBarGraph::set_colour(std::uint8_t graphColour) + { + colour = graphColour; + } + + std::uint8_t OutputLinearBarGraph::get_target_line_colour() const + { + return targetLineColour; + } + + void OutputLinearBarGraph::set_target_line_colour(std::uint8_t lineColour) + { + targetLineColour = lineColour; + } + + bool OutputLinearBarGraph::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void OutputLinearBarGraph::set_options(std::uint8_t options) + { + optionsBitfield = options; + } + + void OutputLinearBarGraph::set_option(Options option, bool optionValue) + { + if (optionValue) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint16_t OutputLinearBarGraph::get_variable_reference() const + { + return variableReference; + } + + void OutputLinearBarGraph::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + VirtualTerminalObjectType OutputArchedBarGraph::get_object_type() const + { + return VirtualTerminalObjectType::OutputArchedBarGraph; + } + + std::uint32_t OutputArchedBarGraph::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool OutputArchedBarGraph::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + // Verify the variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_variable_reference()) + { + auto variableObject = get_object_by_id(get_variable_reference(), objectPool); + + if (nullptr != variableObject) + { + if (VirtualTerminalObjectType::NumberVariable != variableObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + // Verify the target value variable reference is a number variable or NULL_OBJECT_ID + if (NULL_OBJECT_ID != get_target_value_reference()) + { + auto variableObject = get_object_by_id(get_target_value_reference(), objectPool); + + if (nullptr != variableObject) + { + if (VirtualTerminalObjectType::NumberVariable != variableObject->get_object_type()) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if ((nullptr == childObject) || + (VirtualTerminalObjectType::Macro != childObject->get_object_type())) + { + anyWrongChildType = true; + break; + } + } + return (!anyWrongChildType); + } + + bool OutputArchedBarGraph::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Height: + { + set_height(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Colour: + { + set_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::TargetLineColour: + { + set_target_line_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::StartAngle: + { + set_start_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::EndAngle: + { + set_end_angle(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::BarGraphWidth: + { + set_bar_graph_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MinValue: + { + set_min_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::MaxValue: + { + set_max_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::VariableReference: + { + auto variableObject = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != variableObject) && + (VirtualTerminalObjectType::NumberVariable == variableObject->get_object_type()))) + { + set_variable_reference(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::TargetValueVariableReference: + { + set_target_value_reference(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::TargetValue: + { + set_target_value(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool OutputArchedBarGraph::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::Height): + { + returnedAttributeData = get_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::Colour): + { + returnedAttributeData = get_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetLineColour): + { + returnedAttributeData = get_target_line_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::StartAngle): + { + returnedAttributeData = get_start_angle(); + retVal = true; + } + break; + + case static_cast(AttributeName::EndAngle): + { + returnedAttributeData = get_end_angle(); + retVal = true; + } + break; + + case static_cast(AttributeName::BarGraphWidth): + { + returnedAttributeData = get_bar_graph_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::MinValue): + { + returnedAttributeData = get_min_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::MaxValue): + { + returnedAttributeData = get_max_value(); + retVal = true; + } + break; + + case static_cast(AttributeName::VariableReference): + { + returnedAttributeData = get_variable_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetValueVariableReference): + { + returnedAttributeData = get_target_value_reference(); + retVal = true; + } + break; + + case static_cast(AttributeName::TargetValue): + { + returnedAttributeData = get_target_value(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint16_t OutputArchedBarGraph::get_bar_graph_width() const + { + return barGraphWidth; + } + + void OutputArchedBarGraph::set_bar_graph_width(std::uint16_t width) + { + barGraphWidth = width; + } + + std::uint16_t OutputArchedBarGraph::get_min_value() const + { + return minValue; + } + + void OutputArchedBarGraph::set_min_value(std::uint16_t minimumValue) + { + minValue = minimumValue; + } + + std::uint16_t OutputArchedBarGraph::get_max_value() const + { + return maxValue; + } + + void OutputArchedBarGraph::set_max_value(std::uint16_t maximumValue) + { + maxValue = maximumValue; + } + + std::uint16_t OutputArchedBarGraph::get_value() const + { + return value; + } + + void OutputArchedBarGraph::set_value(std::uint16_t aValue) + { + value = aValue; + } + + std::uint8_t OutputArchedBarGraph::get_target_line_colour() const + { + return targetLineColour; + } + + void OutputArchedBarGraph::set_target_line_colour(std::uint8_t value) + { + targetLineColour = value; + } + + std::uint8_t OutputArchedBarGraph::get_colour() const + { + return colour; + } + + void OutputArchedBarGraph::set_colour(std::uint8_t value) + { + colour = value; + } + + bool OutputArchedBarGraph::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void OutputArchedBarGraph::set_options(std::uint8_t options) + { + optionsBitfield = options; + } + + void OutputArchedBarGraph::set_option(Options option, bool optionValue) + { + if (optionValue) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint8_t OutputArchedBarGraph::get_start_angle() const + { + return startAngle; + } + + void OutputArchedBarGraph::set_start_angle(std::uint8_t value) + { + startAngle = value; + } + + std::uint8_t OutputArchedBarGraph::get_end_angle() const + { + return endAngle; + } + + void OutputArchedBarGraph::set_end_angle(std::uint8_t value) + { + endAngle = value; + } + + std::uint16_t OutputArchedBarGraph::get_target_value() const + { + return targetValue; + } + + void OutputArchedBarGraph::set_target_value(std::uint16_t value) + { + targetValue = value; + } + + std::uint16_t OutputArchedBarGraph::get_target_value_reference() const + { + return targetValueReference; + } + + void OutputArchedBarGraph::set_target_value_reference(std::uint16_t value) + { + targetValueReference = value; + } + + std::uint16_t OutputArchedBarGraph::get_variable_reference() const + { + return variableReference; + } + + void OutputArchedBarGraph::set_variable_reference(std::uint16_t variableReferenceValue) + { + variableReference = variableReferenceValue; + } + + VirtualTerminalObjectType PictureGraphic::get_object_type() const + { + return VirtualTerminalObjectType::PictureGraphic; + } + + std::uint32_t PictureGraphic::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool PictureGraphic::get_is_valid(const std::map> &) const + { + return true; + } + + bool PictureGraphic::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Width: + { + set_width(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::TransparencyColour: + { + set_transparency_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool PictureGraphic::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Width): + { + returnedAttributeData = get_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::ActualWidth): + { + returnedAttributeData = get_actual_width(); + retVal = true; + } + break; + + case static_cast(AttributeName::ActualHeight): + { + returnedAttributeData = get_actual_height(); + retVal = true; + } + break; + + case static_cast(AttributeName::Options): + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::TransparencyColour): + { + returnedAttributeData = get_transparency_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::Format): + { + returnedAttributeData = static_cast(get_format()); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::vector &PictureGraphic::get_raw_data() + { + return rawData; + } + + void PictureGraphic::set_raw_data(const std::uint8_t *data, std::uint32_t size) + { + rawData.clear(); + rawData.resize(size); + + for (std::uint32_t i = 0; i < size; i++) + { + rawData[i] = data[i]; + } + } + + void PictureGraphic::add_raw_data(std::uint8_t dataByte) + { + rawData.push_back(dataByte); + } + + std::uint32_t PictureGraphic::get_number_of_bytes_in_raw_data() const + { + return numberOfBytesInRawData; + } + + void PictureGraphic::set_number_of_bytes_in_raw_data(std::uint32_t value) + { + numberOfBytesInRawData = value; + rawData.reserve(value); + } + + std::uint16_t PictureGraphic::get_actual_width() const + { + return actualWidth; + } + + void PictureGraphic::set_actual_width(std::uint16_t value) + { + actualWidth = value; + } + + std::uint16_t PictureGraphic::get_actual_height() const + { + return actualHeight; + } + + void PictureGraphic::set_actual_height(std::uint16_t value) + { + actualHeight = value; + } + + PictureGraphic::Format PictureGraphic::get_format() const + { + return static_cast(formatByte); + } + + void PictureGraphic::set_format(Format value) + { + formatByte = static_cast(value); + } + + bool PictureGraphic::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void PictureGraphic::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void PictureGraphic::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + std::uint8_t PictureGraphic::get_transparency_colour() const + { + return transparencyColour; + } + + void PictureGraphic::set_transparency_colour(std::uint8_t value) + { + transparencyColour = value; + } + + VirtualTerminalObjectType NumberVariable::get_object_type() const + { + return VirtualTerminalObjectType::NumberVariable; + } + + std::uint32_t NumberVariable::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool NumberVariable::get_is_valid(const std::map> &) const + { + return true; + } + + bool NumberVariable::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool NumberVariable::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::Value): + { + returnedAttributeData = get_value(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint32_t NumberVariable::get_value() const + { + return value; + } + + void NumberVariable::set_value(std::uint32_t aValue) + { + value = aValue; + } + + VirtualTerminalObjectType StringVariable::get_object_type() const + { + return VirtualTerminalObjectType::StringVariable; + } + + std::uint32_t StringVariable::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool StringVariable::get_is_valid(const std::map> &) const + { + return true; + } + + bool StringVariable::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool StringVariable::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::string StringVariable::get_value() const + { + return value; + } + + void StringVariable::set_value(const std::string &aValue) + { + value = aValue; + } + + VirtualTerminalObjectType FontAttributes::get_object_type() const + { + return VirtualTerminalObjectType::FontAttributes; + } + + std::uint32_t FontAttributes::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool FontAttributes::get_is_valid(const std::map> &) const + { + return true; + } + + bool FontAttributes::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::FontColour: + { + set_colour(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontSize: + { + if (rawAttributeData <= static_cast(FontAttributes::FontSize::Size128x192)) + { + set_size(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + case AttributeName::FontType: + { + set_type(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FontStyle: + { + set_style(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool FontAttributes::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::FontColour): + { + returnedAttributeData = get_colour(); + retVal = true; + } + break; + + case static_cast(AttributeName::FontSize): + { + returnedAttributeData = static_cast(get_size()); + retVal = true; + } + break; + + case static_cast(AttributeName::FontType): + { + returnedAttributeData = static_cast(get_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::FontStyle): + { + returnedAttributeData = get_style(); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + FontAttributes::FontType FontAttributes::get_type() const + { + return static_cast(type); + } + + void FontAttributes::set_type(FontType value) + { + type = static_cast(value); + } + + std::uint8_t FontAttributes::get_style() const + { + return style; + } + + bool FontAttributes::get_style(FontStyleBits styleSetting) const + { + return (style >> static_cast(styleSetting)) & 0x01; + } + + void FontAttributes::set_style(FontStyleBits bit, bool value) + { + style = (static_cast(value) << static_cast(bit)); + } + + void FontAttributes::set_style(std::uint8_t value) + { + style = value; + } + + FontAttributes::FontSize FontAttributes::get_size() const + { + return static_cast(size); + } + + void FontAttributes::set_size(FontSize value) + { + size = static_cast(value); + } + + std::uint8_t FontAttributes::get_colour() const + { + return colour; + } + + void FontAttributes::set_colour(std::uint8_t value) + { + colour = value; + } + + std::uint8_t FontAttributes::get_font_width_pixels() const + { + std::uint8_t retVal = 0; + + switch (static_cast(size)) + { + case FontSize::Size6x8: + { + retVal = 6; + } + break; + + case FontSize::Size8x8: + case FontSize::Size8x12: + { + retVal = 8; + } + break; + + case FontSize::Size12x16: + { + retVal = 12; + } + break; + + case FontSize::Size16x16: + case FontSize::Size16x24: + { + retVal = 16; + } + break; + + case FontSize::Size24x32: + { + retVal = 24; + } + break; + + case FontSize::Size32x32: + case FontSize::Size32x48: + { + retVal = 32; + } + break; + + case FontSize::Size48x64: + { + retVal = 48; + } + break; + + case FontSize::Size64x64: + case FontSize::Size64x96: + { + retVal = 64; + } + break; + + case FontSize::Size96x128: + { + retVal = 96; + } + break; + + case FontSize::Size128x128: + case FontSize::Size128x192: + { + retVal = 128; + } + break; + + default: + break; + } + return retVal; + } + + std::uint8_t FontAttributes::get_font_height_pixels() const + { + std::uint8_t retVal = 0; + + switch (static_cast(size)) + { + case FontSize::Size6x8: + case FontSize::Size8x8: + { + retVal = 8; + } + break; + + case FontSize::Size8x12: + { + retVal = 12; + } + break; + + case FontSize::Size12x16: + case FontSize::Size16x16: + { + retVal = 16; + } + break; + + case FontSize::Size16x24: + { + retVal = 24; + } + break; + + case FontSize::Size24x32: + case FontSize::Size32x32: + { + retVal = 32; + } + break; + + case FontSize::Size32x48: + { + retVal = 48; + } + break; + + case FontSize::Size48x64: + case FontSize::Size64x64: + { + retVal = 64; + } + break; + + case FontSize::Size64x96: + { + retVal = 96; + } + break; + + case FontSize::Size96x128: + case FontSize::Size128x128: + { + retVal = 128; + } + break; + + case FontSize::Size128x192: + { + retVal = 192; + } + break; + + default: + break; + } + return retVal; + } + + VirtualTerminalObjectType LineAttributes::get_object_type() const + { + return VirtualTerminalObjectType::LineAttributes; + } + + std::uint32_t LineAttributes::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool LineAttributes::get_is_valid(const std::map> &) const + { + return true; + } + + bool LineAttributes::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::LineColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::LineWidth: + { + set_width(static_cast(rawAttributeData & 0xFF)); + retVal = true; + } + break; + + case AttributeName::LineArt: + { + set_line_art_bit_pattern(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool LineAttributes::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::LineColour): + { + returnedAttributeData = static_cast(get_background_color()); + retVal = true; + } + break; + + case static_cast(AttributeName::LineWidth): + { + returnedAttributeData = static_cast(get_width()); + retVal = true; + } + break; + + case static_cast(AttributeName::LineArt): + { + returnedAttributeData = static_cast(get_line_art_bit_pattern()); + retVal = true; + } + break; + + default: + { + // Do nothing, return false + } + break; + } + } + return retVal; + } + + std::uint16_t LineAttributes::get_line_art_bit_pattern() const + { + return lineArtBitpattern; + } + + void LineAttributes::set_line_art_bit_pattern(std::uint16_t value) + { + lineArtBitpattern = value; + } + + VirtualTerminalObjectType FillAttributes::get_object_type() const + { + return VirtualTerminalObjectType::FillAttributes; + } + + std::uint32_t FillAttributes::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool FillAttributes::get_is_valid(const std::map> &objectPool) const + { + return ((NULL_OBJECT_ID == get_fill_pattern()) || + ((nullptr != get_object_by_id(get_fill_pattern(), objectPool)) && + (VirtualTerminalObjectType::PictureGraphic == get_object_by_id(get_fill_pattern(), objectPool)->get_object_type()))); + } + + bool FillAttributes::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::FillType: + { + if (rawAttributeData <= static_cast(FillType::FillWithPatternGivenByFillPatternAttribute)) + { + set_type(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::AnyOtherError; + } + } + break; + + case AttributeName::FillColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::FillPattern: + { + auto fillPictureGraphic = get_object_by_id(static_cast(rawAttributeData), objectPool); + + if (NULL_OBJECT_ID == rawAttributeData) + { + set_fill_pattern(static_cast(rawAttributeData)); + retVal = true; + } + else if ((nullptr != fillPictureGraphic) && + (VirtualTerminalObjectType::PictureGraphic == fillPictureGraphic->get_object_type())) + { + set_fill_pattern(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool FillAttributes::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::FillType: + { + returnedAttributeData = static_cast(get_type()); + retVal = true; + } + break; + + case AttributeName::FillColour: + { + returnedAttributeData = static_cast(get_background_color()); + retVal = true; + } + break; + + case AttributeName::FillPattern: + { + returnedAttributeData = static_cast(get_fill_pattern()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + std::uint16_t FillAttributes::get_fill_pattern() const + { + return fillPattern; + } + + void FillAttributes::set_fill_pattern(std::uint16_t value) + { + fillPattern = value; + } + + FillAttributes::FillType FillAttributes::get_type() const + { + return type; + } + + void FillAttributes::set_type(FillType value) + { + type = value; + } + + VirtualTerminalObjectType InputAttributes::get_object_type() const + { + return VirtualTerminalObjectType::InputAttributes; + } + + std::uint32_t InputAttributes::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool InputAttributes::get_is_valid(const std::map> &) const + { + return true; + } + + bool InputAttributes::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool InputAttributes::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::ValidationType: + { + returnedAttributeData = static_cast(get_validation_type()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + std::string InputAttributes::get_validation_string() const + { + return validationString; + } + + void InputAttributes::set_validation_string(const std::string &value) + { + validationString = value; + } + + InputAttributes::ValidationType InputAttributes::get_validation_type() const + { + return validationType; + } + + void InputAttributes::set_validation_type(ValidationType newValidationType) + { + validationType = newValidationType; + } + + VirtualTerminalObjectType ExtendedInputAttributes::get_object_type() const + { + return VirtualTerminalObjectType::ExtendedInputAttributes; + } + + std::uint32_t ExtendedInputAttributes::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool ExtendedInputAttributes::get_is_valid(const std::map> &) const + { + return true; + } + + bool ExtendedInputAttributes::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool ExtendedInputAttributes::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::ValidationType: + { + returnedAttributeData = static_cast(get_validation_type()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + std::uint8_t ExtendedInputAttributes::get_number_of_code_planes() const + { + return static_cast(codePlanes.size()); + } + + void ExtendedInputAttributes::set_number_of_code_planes(std::uint8_t value) + { + codePlanes.resize(value); + } + + ExtendedInputAttributes::ValidationType ExtendedInputAttributes::get_validation_type() const + { + return validationType; + } + + void ExtendedInputAttributes::set_validation_type(ValidationType value) + { + validationType = value; + } + + VirtualTerminalObjectType ObjectPointer::get_object_type() const + { + return VirtualTerminalObjectType::ObjectPointer; + } + + std::uint32_t ObjectPointer::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool ObjectPointer::get_is_valid(const std::map> &objectPool) const + { + return ((NULL_OBJECT_ID == value) || (nullptr != get_object_by_id(value, objectPool))); + } + + bool ObjectPointer::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + std::uint16_t ObjectPointer::get_value() const + { + return value; + } + + void ObjectPointer::set_value(std::uint16_t objectIDToPointTo) + { + value = objectIDToPointTo; + } + + bool ObjectPointer::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::Value: + { + if (get_number_children() > 0) + { + returnedAttributeData = get_child_id(0); + } + else + { + returnedAttributeData = NULL_OBJECT_ID; + } + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + VirtualTerminalObjectType ExternalObjectPointer::get_object_type() const + { + return VirtualTerminalObjectType::ExternalObjectPointer; + } + + std::uint32_t ExternalObjectPointer::get_minumum_object_length() const + { + return 9; + } + + bool ExternalObjectPointer::get_is_valid(const std::map> &objectPool) const + { + bool isDefaultObjectValid = (NULL_OBJECT_ID == get_default_object_id()) || + (nullptr != objectPool.at(get_default_object_id())); + bool isExternalNAMEIDValid = (NULL_OBJECT_ID == get_external_reference_name_id()) || + (nullptr != objectPool.at(get_external_reference_name_id())); + return (isDefaultObjectValid && isExternalNAMEIDValid); + } + + bool ExternalObjectPointer::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::DefaultObjectID: + { + if ((NULL_OBJECT_ID == rawAttributeData) || + (nullptr != get_object_by_id(static_cast(rawAttributeData), objectPool))) + { + set_default_object_id(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::ExternalReferenceNAMEID: + { + if ((NULL_OBJECT_ID == rawAttributeData) || + (nullptr != get_object_by_id(static_cast(rawAttributeData), objectPool))) + { + set_external_reference_name_id(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + break; + + case AttributeName::ExternalObjectID: + { + set_external_object_id(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool ExternalObjectPointer::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::DefaultObjectID: + { + returnedAttributeData = static_cast(get_default_object_id()); + retVal = true; + } + break; + + case AttributeName::ExternalReferenceNAMEID: + { + returnedAttributeData = static_cast(get_external_reference_name_id()); + retVal = true; + } + break; + + case AttributeName::ExternalObjectID: + { + returnedAttributeData = static_cast(get_external_object_id()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + std::uint16_t ExternalObjectPointer::get_default_object_id() const + { + return defaultObjectID; + } + + void ExternalObjectPointer::set_default_object_id(std::uint16_t id) + { + defaultObjectID = id; + } + + std::uint16_t ExternalObjectPointer::get_external_reference_name_id() const + { + return externalReferenceNAMEID; + } + + void ExternalObjectPointer::set_external_reference_name_id(std::uint16_t id) + { + externalReferenceNAMEID = id; + } + + std::uint16_t ExternalObjectPointer::get_external_object_id() const + { + return externalObjectID; + } + + void ExternalObjectPointer::set_external_object_id(std::uint16_t id) + { + externalObjectID = id; + } + + const std::array Macro::ALLOWED_COMMANDS_LOOKUP_TABLE = { + static_cast(Command::HideShowObject), + static_cast(Command::EnableDisableObject), + static_cast(Command::SelectInputObject), + static_cast(Command::ControlAudioSignal), + static_cast(Command::SetAudioVolume), + static_cast(Command::ChangeChildLocation), + static_cast(Command::ChangeSize), + static_cast(Command::ChangeBackgroundColour), + static_cast(Command::ChangeNumericValue), + static_cast(Command::ChangeEndPoint), + static_cast(Command::ChangeFontAttributes), + static_cast(Command::ChangeLineAttributes), + static_cast(Command::ChangeFillAttributes), + static_cast(Command::ChangeActiveMask), + static_cast(Command::ChangeSoftKeyMask), + static_cast(Command::ChangeAttribute), + static_cast(Command::ChangePriority), + static_cast(Command::ChangeListItem), + static_cast(Command::ChangeStringValue), + static_cast(Command::ChangeChildPosition), + static_cast(Command::ChangeObjectLabel), + static_cast(Command::ChangePolygonPoint), + static_cast(Command::LockUnlockMask), + static_cast(Command::ExecuteMacro), + static_cast(Command::ChangePolygonScale), + static_cast(Command::GraphicsContextCommand), + static_cast(Command::SelectColourMap), + static_cast(Command::ExecuteExtendedMacro) + }; + + VirtualTerminalObjectType Macro::get_object_type() const + { + return VirtualTerminalObjectType::Macro; + } + + std::uint32_t Macro::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool Macro::get_is_valid(const std::map> &) const + { + return get_are_command_packets_valid(); + } + + bool Macro::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool Macro::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + bool Macro::add_command_packet(const std::vector &command) + { + bool retVal = false; + + if (commandPackets.size() < 255) + { + commandPackets.push_back(command); + retVal = true; + } + return retVal; + } + + std::uint8_t Macro::get_number_of_commands() const + { + return static_cast(commandPackets.size()); + } + + bool Macro::get_command_packet(std::uint8_t index, std::vector &command) + { + bool retVal = false; + + if (index < commandPackets.size()) + { + command = commandPackets.at(index); + retVal = true; + } + return retVal; + } + + bool Macro::remove_command_packet(std::uint8_t index) + { + bool retVal = false; + + if (index < commandPackets.size()) + { + auto eraseLocation = commandPackets.begin() + index; + commandPackets.erase(eraseLocation); + retVal = true; + } + return retVal; + } + + bool Macro::get_are_command_packets_valid() const + { + bool retVal = true; + + if (commandPackets.empty()) + { + retVal = true; + } + else + { + for (const auto &command : commandPackets) + { + bool currentCommandAllowed = false; + + for (const auto &allowedCommand : ALLOWED_COMMANDS_LOOKUP_TABLE) + { + if (!command.empty() && (command.at(0) == allowedCommand)) + { + currentCommandAllowed = true; + break; + } + } + + if (!currentCommandAllowed) + { + retVal = false; + break; + } + } + } + return retVal; + } + + VirtualTerminalObjectType ColourMap::get_object_type() const + { + return VirtualTerminalObjectType::ColourMap; + } + + std::uint32_t ColourMap::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool ColourMap::get_is_valid(const std::map> &) const + { + return true; + } + + bool ColourMap::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; + } + + bool ColourMap::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + bool ColourMap::set_number_of_colour_indexes(std::uint16_t value) + { + bool retVal = false; + + if ((value != colourMapData.size()) && + ((2 == value) || + (16 == value) || + (256 == value))) + { + colourMapData.clear(); + colourMapData.resize(value); + + for (std::size_t i = 0; i < colourMapData.size(); i++) + { + colourMapData[i] = static_cast(i); + } + retVal = true; + } + return retVal; + } + + std::uint16_t ColourMap::get_number_of_colour_indexes() const + { + return static_cast(colourMapData.size()); + } + + bool ColourMap::set_colour_map_index(std::uint8_t index, std::uint8_t value) + { + bool retVal = false; + + if (index < colourMapData.size()) + { + colourMapData[index] = value; + retVal = true; + } + return retVal; + } + + std::uint8_t ColourMap::get_colour_map_index(std::uint8_t index) const + { + std::uint8_t retVal = 0; + + if (index < get_number_of_colour_indexes()) + { + retVal = colourMapData[index]; + } + return retVal; + } + + VirtualTerminalObjectType WindowMask::get_object_type() const + { + return VirtualTerminalObjectType::WindowMask; + } + + std::uint32_t WindowMask::get_minumum_object_length() const + { + return MIN_OBJECT_LENGTH; + } + + bool WindowMask::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + if (WindowType::Freeform != get_window_type()) + { + if (NULL_OBJECT_ID != title) + { + auto titleObject = get_object_by_id(title, objectPool); + + if (nullptr != titleObject) + { + if ((VirtualTerminalObjectType::ObjectPointer != titleObject->get_object_type()) && + (VirtualTerminalObjectType::OutputString != titleObject->get_object_type())) + { + anyWrongChildType = true; + } + else if (VirtualTerminalObjectType::ObjectPointer == titleObject->get_object_type()) + { + if (0 == titleObject->get_number_children()) + { + anyWrongChildType = true; + } + else + { + std::uint16_t titleObjectPointedTo = std::static_pointer_cast(titleObject)->get_child_id(0); + auto child = get_object_by_id(titleObjectPointedTo, objectPool); + + if ((nullptr != child) && (VirtualTerminalObjectType::OutputString == child->get_object_type())) + { + // Valid + } + else + { + anyWrongChildType = true; + } + } + } + else + { + // Valid + } + } + else + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + + if (NULL_OBJECT_ID != name) + { + auto nameObject = get_object_by_id(name, objectPool); + + if (nullptr != nameObject) + { + if ((VirtualTerminalObjectType::ObjectPointer != nameObject->get_object_type()) && + (VirtualTerminalObjectType::OutputString != nameObject->get_object_type())) + { + anyWrongChildType = true; + } + else if (VirtualTerminalObjectType::ObjectPointer == nameObject->get_object_type()) + { + if (0 == nameObject->get_number_children()) + { + anyWrongChildType = true; + } + else + { + std::uint16_t titleObjectPointedTo = std::static_pointer_cast(nameObject)->get_child_id(0); + auto child = get_object_by_id(titleObjectPointedTo, objectPool); + + if ((nullptr != child) && (VirtualTerminalObjectType::OutputString == child->get_object_type())) + { + // Valid + } + else + { + anyWrongChildType = true; + } + } + } + else + { + // Valid + } + } + else + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + + if (NULL_OBJECT_ID != icon) + { + auto nameObject = get_object_by_id(icon, objectPool); + + if (nullptr != nameObject) + { + switch (nameObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::Container: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::GraphicsContext: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ScaledGraphic: + { + // Valid + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + else + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + else if (NULL_OBJECT_ID != title) + { + anyWrongChildType = true; + } + + // Validate the actual child object references for each window type + switch (static_cast(windowType)) + { + case WindowType::Freeform: + { + // Basically anything goes + } + break; + + case WindowType::NumericOutputValueWithUnits1x1: + case WindowType::NumericOutputValueWithUnits2x1: + { + if (2 == get_number_children()) + { + auto outputNum = get_object_by_id(get_child_id(0), objectPool); + auto outputString = get_object_by_id(get_child_id(1), objectPool); + + if ((nullptr == outputNum) || + (nullptr == outputString) || + (VirtualTerminalObjectType::OutputNumber != outputNum->get_object_type()) || + (VirtualTerminalObjectType::OutputString != outputString->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::NumericOutputValueNoUnits1x1: + case WindowType::NumericOutputValueNoUnits2x1: + { + if (1 == get_number_children()) + { + auto outputNum = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == outputNum) || + (VirtualTerminalObjectType::OutputNumber != outputNum->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::StringOutputValue1x1: + case WindowType::StringOutputValue2x1: + { + if (1 == get_number_children()) + { + auto outputString = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == outputString) || + (VirtualTerminalObjectType::OutputString != outputString->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::NumericInputValueWithUnits1x1: + case WindowType::NumericInputValueWithUnits2x1: + { + if (2 == get_number_children()) + { + auto inputNum = get_object_by_id(get_child_id(0), objectPool); + auto outputString = get_object_by_id(get_child_id(1), objectPool); + + if ((nullptr == inputNum) || + (nullptr == outputString) || + (VirtualTerminalObjectType::InputNumber != inputNum->get_object_type()) || + (VirtualTerminalObjectType::OutputString != outputString->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::NumericInputValueNoUnits1x1: + case WindowType::NumericInputValueNoUnits2x1: + { + if (1 == get_number_children()) + { + auto inputNum = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == inputNum) || + (VirtualTerminalObjectType::InputNumber != inputNum->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::StringInputValue1x1: + case WindowType::StringInputValue2x1: + { + if (1 == get_number_children()) + { + auto inputStr = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == inputStr) || + (VirtualTerminalObjectType::InputString != inputStr->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::HorizontalLinearBarGraphNoUnits1x1: + case WindowType::HorizontalLinearBarGraphNoUnits2x1: + { + if (1 == get_number_children()) + { + auto outputBargraph = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == outputBargraph) || + (VirtualTerminalObjectType::OutputLinearBarGraph != outputBargraph->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::SingleButton1x1: + case WindowType::SingleButton2x1: + { + if (1 == get_number_children()) + { + auto button = get_object_by_id(get_child_id(0), objectPool); + + if ((nullptr == button) || + (VirtualTerminalObjectType::Button != button->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + case WindowType::DoubleButton1x1: + case WindowType::DoubleButton2x1: + { + if (2 == get_number_children()) + { + auto button1 = get_object_by_id(get_child_id(0), objectPool); + auto button2 = get_object_by_id(get_child_id(1), objectPool); + + if ((nullptr == button1) || + (nullptr == button2) || + (VirtualTerminalObjectType::Button != button1->get_object_type()) || + (VirtualTerminalObjectType::Button != button2->get_object_type())) + { + anyWrongChildType = true; + } + } + else + { + anyWrongChildType = true; + } + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + return !anyWrongChildType; + } + + bool WindowMask::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::BackgroundColour: + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Options: + { + set_options(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case AttributeName::Name: + { + set_name_object_id(static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool WindowMask::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID < static_cast(AttributeName::NumberOfAttributes)) + { + switch (static_cast(attributeID)) + { + case AttributeName::Type: + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case AttributeName::BackgroundColour: + { + returnedAttributeData = static_cast(get_background_color()); + retVal = true; + } + break; + + case AttributeName::Options: + { + returnedAttributeData = optionsBitfield; + retVal = true; + } + break; + + case AttributeName::Name: + { + returnedAttributeData = static_cast(get_name_object_id()); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + } + return retVal; + } + + std::uint16_t WindowMask::get_name_object_id() const + { + return name; + } + + void WindowMask::set_name_object_id(std::uint16_t object) + { + name = object; + } + + std::uint16_t WindowMask::get_title_object_id() const + { + return title; + } + + void WindowMask::set_title_object_id(std::uint16_t object) + { + title = object; + } + + std::uint16_t WindowMask::get_icon_object_id() const + { + return icon; + } + + void WindowMask::set_icon_object_id(std::uint16_t object) + { + icon = object; + } + + WindowMask::WindowType WindowMask::get_window_type() const + { + return static_cast(windowType); + } + + void WindowMask::set_window_type(WindowType type) + { + if (static_cast(type) <= static_cast(WindowType::DoubleButton2x1)) + { + windowType = static_cast(type); + } + } + + bool WindowMask::get_option(Options option) const + { + return (0 != ((1 << static_cast(option)) & optionsBitfield)); + } + + void WindowMask::set_options(std::uint8_t value) + { + optionsBitfield = value; + } + + void WindowMask::set_option(Options option, bool value) + { + if (value) + { + optionsBitfield |= (1 << static_cast(option)); + } + else + { + optionsBitfield &= ~(1 << static_cast(option)); + } + } + + VirtualTerminalObjectType AuxiliaryFunctionType1::get_object_type() const + { + return VirtualTerminalObjectType::AuxiliaryFunctionType1; + } + + std::uint32_t AuxiliaryFunctionType1::get_minumum_object_length() const + { + return 6; + } + + bool AuxiliaryFunctionType1::get_is_valid(const std::map> &objectPool) const + { + // Despite modern VTs not using this object, we still have to validate it. + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::PictureGraphic: + { + // Valid + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + else + { + anyWrongChildType = true; // Some invalid child ID + break; + } + } + return !anyWrongChildType; + } + + bool AuxiliaryFunctionType1::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; // All attributes are read only + } + + bool AuxiliaryFunctionType1::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID == static_cast(AttributeName::Type)) + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + return retVal; + } + + AuxiliaryFunctionType1::FunctionType AuxiliaryFunctionType1::get_function_type() const + { + return functionType; + } + + void AuxiliaryFunctionType1::set_function_type(FunctionType type) + { + functionType = type; + } + + VirtualTerminalObjectType AuxiliaryFunctionType2::get_object_type() const + { + return VirtualTerminalObjectType::AuxiliaryFunctionType2; + } + + std::uint32_t AuxiliaryFunctionType2::get_minumum_object_length() const + { + return 6; + } + + bool AuxiliaryFunctionType2::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ScaledGraphic: + { + // Valid + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + else + { + anyWrongChildType = true; // Some invalid child ID + break; + } + } + return !anyWrongChildType; + } + + bool AuxiliaryFunctionType2::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + if (attributeID == static_cast(AttributeName::BackgroundColour)) + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidAttributeID; + } + return retVal; + } + + bool AuxiliaryFunctionType2::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = static_cast(get_background_color()); + retVal = true; + } + break; + + case static_cast(AttributeName::FunctionAttributes): + { + returnedAttributeData = functionAttributesBitfield; + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + return retVal; + } + + AuxiliaryFunctionType2::FunctionType AuxiliaryFunctionType2::get_function_type() const + { + return static_cast(functionAttributesBitfield & 0x1F); + } + + void AuxiliaryFunctionType2::set_function_type(FunctionType type) + { + functionAttributesBitfield &= 0xE0; + functionAttributesBitfield |= static_cast(type) & 0x1F; + } + + bool AuxiliaryFunctionType2::get_function_attribute(FunctionAttribute attributeToCheck) const + { + return (0 != ((1 << static_cast(attributeToCheck)) & functionAttributesBitfield)); + } + + void AuxiliaryFunctionType2::set_function_attribute(FunctionAttribute attributeToSet, bool value) + { + if (value) + { + functionAttributesBitfield |= (1 << static_cast(attributeToSet)); + } + else + { + functionAttributesBitfield &= ~(1 << static_cast(attributeToSet)); + } + } + + VirtualTerminalObjectType AuxiliaryInputType1::get_object_type() const + { + return VirtualTerminalObjectType::AuxiliaryInputType1; + } + + std::uint32_t AuxiliaryInputType1::get_minumum_object_length() const + { + return 7; + } + + bool AuxiliaryInputType1::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::PictureGraphic: + { + // Valid + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + else + { + anyWrongChildType = true; // Some invalid child ID + break; + } + } + return !anyWrongChildType; + } + + bool AuxiliaryInputType1::set_attribute(std::uint8_t, std::uint32_t, const std::map> &, AttributeError &returnedError) + { + returnedError = AttributeError::InvalidAttributeID; + return false; // All attributes are read only + } + + bool AuxiliaryInputType1::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + if (attributeID == static_cast(AttributeName::Type)) + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + return retVal; + } + + AuxiliaryInputType1::FunctionType AuxiliaryInputType1::get_function_type() const + { + return functionType; + } + + void AuxiliaryInputType1::set_function_type(FunctionType type) + { + functionType = type; + } + + std::uint8_t AuxiliaryInputType1::get_input_id() const + { + return inputID; + } + + bool AuxiliaryInputType1::set_input_id(std::uint8_t id) + { + bool retVal = false; + + if (id <= 250) // The range is defined in ISO 11783-6 table J.3 + { + inputID = id; + retVal = true; + } + return retVal; + } + + VirtualTerminalObjectType AuxiliaryInputType2::get_object_type() const + { + return VirtualTerminalObjectType::AuxiliaryInputType2; + } + + std::uint32_t AuxiliaryInputType2::get_minumum_object_length() const + { + return 6; + } + + bool AuxiliaryInputType2::get_is_valid(const std::map> &objectPool) const + { + bool anyWrongChildType = false; + + for (const auto &child : children) + { + auto childObject = get_object_by_id(child.id, objectPool); + + if (nullptr != childObject) + { + switch (childObject->get_object_type()) + { + case VirtualTerminalObjectType::OutputString: + case VirtualTerminalObjectType::OutputNumber: + case VirtualTerminalObjectType::OutputLine: + case VirtualTerminalObjectType::OutputList: + case VirtualTerminalObjectType::OutputRectangle: + case VirtualTerminalObjectType::OutputEllipse: + case VirtualTerminalObjectType::OutputPolygon: + case VirtualTerminalObjectType::OutputMeter: + case VirtualTerminalObjectType::OutputLinearBarGraph: + case VirtualTerminalObjectType::OutputArchedBarGraph: + case VirtualTerminalObjectType::PictureGraphic: + case VirtualTerminalObjectType::ObjectPointer: + case VirtualTerminalObjectType::ScaledGraphic: + { + // Valid + } + break; + + default: + { + anyWrongChildType = true; + } + break; + } + } + else + { + anyWrongChildType = true; // Some invalid child ID + break; + } + } + return !anyWrongChildType; + } + + bool AuxiliaryInputType2::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &, AttributeError &returnedError) + { + bool retVal = false; + + switch (attributeID) + { + case static_cast(AttributeName::BackgroundColour): + { + set_background_color(static_cast(rawAttributeData)); + retVal = true; + } + break; + + case static_cast(AttributeName::FunctionAttributes): + { + functionAttributesBitfield = (static_cast(rawAttributeData)); + retVal = true; + } + break; + + default: + { + returnedError = AttributeError::InvalidAttributeID; + } + break; + } + return retVal; + } + + bool AuxiliaryInputType2::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::FunctionAttributes): + { + returnedAttributeData = functionAttributesBitfield; + retVal = true; + } + break; + + case static_cast(AttributeName::BackgroundColour): + { + returnedAttributeData = get_background_color(); + retVal = true; + } + break; + + default: + { + // Do nothing return false + } + break; + } + return retVal; + } + + AuxiliaryFunctionType2::FunctionType AuxiliaryInputType2::get_function_type() const + { + return static_cast(functionAttributesBitfield & 0x1F); + } + + void AuxiliaryInputType2::set_function_type(AuxiliaryFunctionType2::FunctionType type) + { + functionAttributesBitfield &= 0xE0; + functionAttributesBitfield |= static_cast(type) & 0x1F; + } + + bool AuxiliaryInputType2::get_function_attribute(FunctionAttribute attributeToCheck) const + { + return (0 != ((1 << static_cast(attributeToCheck)) & functionAttributesBitfield)); + } + + void AuxiliaryInputType2::set_function_attribute(FunctionAttribute attributeToSet, bool value) + { + if (value) + { + functionAttributesBitfield |= (1 << static_cast(attributeToSet)); + } + else + { + functionAttributesBitfield &= ~(1 << static_cast(attributeToSet)); + } + } + + VirtualTerminalObjectType AuxiliaryControlDesignatorType2::get_object_type() const + { + return VirtualTerminalObjectType::AuxiliaryControlDesignatorType2; + } + + std::uint32_t AuxiliaryControlDesignatorType2::get_minumum_object_length() const + { + return 6; + } + + bool AuxiliaryControlDesignatorType2::get_is_valid(const std::map> &objectPool) const + { + bool retVal = (((NULL_OBJECT_ID == auxiliaryObjectID) || ((nullptr != get_object_by_id(auxiliaryObjectID, objectPool)))) && (pointerType <= 3)); + + if (retVal) + { + // Check the referenced object is valid + auto object = get_object_by_id(auxiliaryObjectID, objectPool); + + if ((VirtualTerminalObjectType::AuxiliaryFunctionType2 == object->get_object_type()) || + (VirtualTerminalObjectType::AuxiliaryInputType2 == object->get_object_type())) + { + // Valid + } + else + { + retVal = false; + } + } + return retVal; + } + + bool AuxiliaryControlDesignatorType2::set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) + { + bool retVal = false; + returnedError = AttributeError::InvalidAttributeID; + + if (static_cast(AttributeName::AuxiliaryObjectID) == attributeID) + { + if ((NULL_OBJECT_ID == rawAttributeData) || + ((nullptr != get_object_by_id(static_cast(rawAttributeData), objectPool)) && + ((VirtualTerminalObjectType::AuxiliaryFunctionType2 == objectPool.at(static_cast(rawAttributeData))->get_object_type()) || + (VirtualTerminalObjectType::AuxiliaryInputType2 == objectPool.at(static_cast(rawAttributeData))->get_object_type())))) + { + set_auxiliary_object_id(static_cast(rawAttributeData)); + retVal = true; + } + else + { + returnedError = AttributeError::InvalidValue; + } + } + return retVal; + } + + bool AuxiliaryControlDesignatorType2::get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const + { + bool retVal = false; + + switch (attributeID) + { + case static_cast(AttributeName::Type): + { + returnedAttributeData = static_cast(get_object_type()); + retVal = true; + } + break; + + case static_cast(AttributeName::PointerType): + { + returnedAttributeData = get_pointer_type(); + retVal = true; + } + break; + + case static_cast(AttributeName::AuxiliaryObjectID): + { + returnedAttributeData = get_auxiliary_object_id(); + retVal = true; + } + break; + + default: + { + // Invalid attribute ID + } + break; + } + return retVal; + } + + std::uint16_t AuxiliaryControlDesignatorType2::get_auxiliary_object_id() const + { + return auxiliaryObjectID; + } + + void AuxiliaryControlDesignatorType2::set_auxiliary_object_id(std::uint16_t id) + { + auxiliaryObjectID = id; + } + + std::uint8_t AuxiliaryControlDesignatorType2::get_pointer_type() const + { + return pointerType; + } + + void AuxiliaryControlDesignatorType2::set_pointer_type(std::uint8_t type) + { + pointerType = type; + } + +} // namespace isobus diff --git a/src/isobus_virtual_terminal_objects.hpp b/src/isobus_virtual_terminal_objects.hpp index 9f2a1dd..a50c930 100644 --- a/src/isobus_virtual_terminal_objects.hpp +++ b/src/isobus_virtual_terminal_objects.hpp @@ -1,7 +1,7 @@ //================================================================================================ /// @file isobus_virtual_terminal_objects.hpp /// -/// @brief Enumerates the different VT object types that can comprise a VT object pool +/// @brief Defines the different VT object types that can comprise a VT object pool. /// @author Adrian Del Grosso /// /// @copyright 2023 Adrian Del Grosso @@ -9,12 +9,20 @@ #ifndef ISOBUS_VIRTUAL_TERMINAL_OBJECTS_HPP #define ISOBUS_VIRTUAL_TERMINAL_OBJECTS_HPP +#include "can_constants.hpp" + +#include +#include +#include +#include +#include + namespace isobus { /// @brief The types of objects in an object pool by object type byte value - enum class VirtualTerminalObjectType + enum class VirtualTerminalObjectType : std::uint8_t { - WorkingSet = 0, ///< Top level object that describes an implement’s ECU or group of ECUs + WorkingSet = 0, ///< Top level object that describes an implement’s ECU or group of ECUs DataMask = 1, ///< Top level object that contains other objects. A Data Mask is activated by a Working Set to become the active set of objects on the VT display. AlarmMask = 2, ///< Top level object that contains other objects. Describes an alarm display. Container = 3, ///< Used to group objects. @@ -40,6 +48,8 @@ namespace isobus GraphicsContext = 36, ///< Used to output a graphics context. Animation = 44, ///< The Animation object is used to display simple animations PictureGraphic = 20, ///< Used to output a picture graphic (bitmap). + GraphicData = 46, ///< Used to define the data for a graphic image + ScaledGraphic = 48, ///< Used to display a scaled representation of a graphic object NumberVariable = 21, ///< Used to store a 32-bit unsigned integer value. StringVariable = 22, ///< Used to store a fixed length string value. FontAttributes = 23, ///< Used to group font based attributes. Can only be referenced by other objects. @@ -76,6 +86,4737 @@ namespace isobus ManufacturerDefined15 = 254, ///< Manufacturer defined objects should not be sent to any other Vendors VT Reserved = 255 ///< Reserved for future use. (See Clause D.14 Get Supported Objects message) }; + + /// @brief Enumerates VT events. Events can be uniquely associated with a Macro object to execute when the event occurs. + /// These are defined in ISO 11783-6:2018 Table A.2 + enum class EventID : std::uint8_t + { + Reserved = 0, ///< Reserved + OnActivate = 1, ///< Working set is made active + OnDeactivate = 2, ///< Working set is made inactive + OnShow = 3, ///< For Container objects, triggered by the hide/show command, with "show" indicated; For mask objects, when the mask is made visible on the display. + OnHide = 4, ///< For Container objects, triggered by the hide/show command, with "hide" indicated; for mask objects, when the mask is removed from the display. + // OnRefresh - An object that is already on display is redrawn (Macros cannot be associated with this event so no event ID is defined). + OnEnable = 5, ///< Input object is enabled (only enabled input objects can be navigated to). An Animation object is enabled for animation + OnDisable = 6, ///< Input object is disabled (only enabled input objects can be navigated to). An Animation object is disabled for animation. + OnChangeActiveMask = 7, ///< Change Active mask command + OnChangeSoftKeyMask = 8, ///< Change Soft Key mask command + OnChangeAttribute = 9, ///< Change Attribute command + OnChangeBackgroundColour = 10, ///< Change Background Colour command + ChangeFontAttributes = 11, ///< Change Font Attributes command + ChangeLineAttributes = 12, ///< Change Line Attributes command + ChangeFillAttributes = 13, ///< Change Fill Attributes command + ChangeChildLocation = 14, ///< Change Child Location command + OnChangeSize = 15, ///< Change Size command + OnChangeValue = 16, ///< Change numeric value or change string value command + OnChangePriority = 17, ///< Change Priority command + OnChangeEndpoint = 18, ///< Change Endpoint command + OnInputFieldSelection = 19, ///< The input field, Key or Button has received focus, operator has navigated onto the input field or Button or the VT has received the Select Input Object command. + OnInputFieldDeselection = 20, ///< The input field, Key or Button has lost focus, operator has navigated off of the input field or Button or the VT has received the Select Input Object command + OnESC = 21, ///< Input aborted on an input field either by the operator or the Working Set. + OnEntryOfAValue = 22, ///< Operator completes entry by activating the ENTER means - value does not have to change + OnEntryOfANewValue = 23, ///< Operator completes entry by activating the ENTER means - value has changed + OnKeyPress = 24, ///< A Soft Key or Button is pressed + OnKeyRelease = 25, ///< A Soft Key or Button is released + OnChangeChildPosition = 26, ///< Change Child Position command + OnPointingEventPress = 27, ///< Operator touches/clicks an area that causes a pointing event + OnPointingEventRelease = 28, ///< Operator touch/click is released + ProprietaryRangeBegin = 240, ///< Proprietary range begin + ProprietaryRangeEnd = 254, ///< Proprietary range end + UseExtendedMacroReference = 255 ///< This is not an event. When value is found in the event list of an object, it indicates that a 16 bit Macro Object ID reference is used + }; + + /// @brief A helper structure to group a macro ID with an event ID + struct MacroMetadata + { + EventID event; ///< The event that triggers this macro + std::uint16_t macroID; ///< The ID of the macro to execute + }; + + /// @brief VT 3 component colour vector + class VTColourVector + { + public: + float r; ///< Red value for a pixel, range 0.0f to 1.0f + float g; ///< Green value for a pixel, range 0.0f to 1.0f + float b; ///< Blue value for a pixel, range 0.0f to 1.0f + + /// @brief Default constructor for a VT Colour, which produces the colour black + constexpr VTColourVector() : + r(0.0f), g(0.0f), b(0.0f) {} + + /// @brief Constructor for a VT Colour which initializes to an arbitrary colour + /// @param[in] red The red value for a pixel, range 0.0f to 1.0f + /// @param[in] green The green value for a pixel, range 0.0f to 1.0f + /// @param[in] blue The blue value for a pixel, range 0.0f to 1.0f + constexpr VTColourVector(float red, float green, float blue) : + r(red), g(green), b(blue) {} + }; + + /// @brief An object that represents the VT's active colour table + class VTColourTable + { + public: + /// @brief Constructor for a VT colour table + VTColourTable(); + + /// @brief Returns the colour vector associated to the specified VT colour index, which + /// is what gets provided normally in most VT CAN messages, so this essentially maps the index + /// to an actually usable colour definition. + /// @param[in] colourIndex The VT colour index to retrieve + /// @returns An RGB colour vector associated to the specified VT colour index + VTColourVector get_colour(std::uint8_t colourIndex) const; + + /// @brief Sets the specified VT colour index to a new RGB colour value + /// @param[in] colourIndex The VT colour index to modify + /// @param[in] newColour The RGB colour to set the specified index to + void set_colour(std::uint8_t colourIndex, VTColourVector newColour); + + private: + static constexpr std::size_t VT_COLOUR_TABLE_SIZE = 256; ///< The size of the VT colour table as specified in ISO11783-6 + + std::array colourTable; ///< Colour table data. Associates VT colour index with RGB value. + }; + + /// @brief Generic VT object base class + class VTObject + { + public: + /// @brief Enumerates the bit indices of the error fields that can be set when changing an attribute + enum class AttributeError : std::uint8_t + { + InvalidObjectID = 0, + InvalidAttributeID = 1, + InvalidValue = 2, + AnyOtherError = 4 + }; + + /// @brief Constructor for a generic VT object. Sets up default values and the pointer to the member object pool + VTObject() = default; + + /// @brief Virtual destructor for a generic VT object + virtual ~VTObject() = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + virtual VirtualTerminalObjectType get_object_type() const = 0; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + virtual std::uint32_t get_minumum_object_length() const = 0; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool A map of all objects in the current object pool, keyed by their object ID + /// @returns `true` if the object passed basic error checks + virtual bool get_is_valid(const std::map> &objectPool) const = 0; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool A map of all objects in the current object pool, keyed by their object ID. Used to validate some object references. + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + virtual bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) = 0; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + virtual bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const = 0; + + /// @brief Returns the object ID of this VT object + /// @returns The object ID of this VT object + std::uint16_t get_id() const; + + /// @brief Sets the object ID of this VT object + /// @param[in] value The new object ID for this object. Must be unique in this pool. + void set_id(std::uint16_t value); + + /// @brief Returns the width of this object in px + /// @returns The width of this object in px + std::uint16_t get_width() const; + + /// @brief Sets the width of this object in px + /// @param[in] value The new width of this object in px + void set_width(std::uint16_t value); + + /// @brief Returns the height of this object in px + /// @returns The height of this object in px + std::uint16_t get_height() const; + + /// @brief Sets the height of this object in px + /// @param[in] value The new height of this object in px + void set_height(std::uint16_t value); + + /// @brief Returns the background color attribute of this object + /// @returns The background color attribute of this object (index to the actual color in the color table) + std::uint8_t get_background_color() const; + + /// @brief Sets the background color attribute of this object + /// @param[in] value The new background color attribute for this object (index to the actual color in the color table) + void set_background_color(std::uint8_t value); + + /// @brief Returns the number of child objects within this object + /// @returns The number of child objects within this object + std::uint16_t get_number_children() const; + + /// @brief Adds an object as a child to another object, which essentially creates a tree of object association + /// @param[in] objectID The object ID of the child to add + /// @param[in] relativeXLocation The X offset of this object to its parent + /// @param[in] relativeYLocation The Y offset of this object to its parent + void add_child(std::uint16_t objectID, std::int16_t relativeXLocation, std::int16_t relativeYLocation); + + /// @brief Returns the ID of the child by index, if one was added previously + /// @note NULL_OBJECT_ID is a valid child, so you should always check the number of children to know if the return value of this is "valid" + /// @param[in] index The index of the child to retrieve + /// @returns The ID of the child at the specified index, or NULL_OBJECT_ID if the index is out of range + std::uint16_t get_child_id(std::uint16_t index) const; + + /// @brief Returns the X offset of the child object associated with the specified index into the parent object + /// @param[in] index The index of the child to retrieve + /// @returns The relative X position of the child, and always 0 if the index is out of range + std::int16_t get_child_x(std::uint16_t index) const; + + /// @brief Returns the Y offset of the child object associated with the specified index into the parent object + /// @param[in] index The index of the child to retrieve + /// @returns The relative Y position of the child, and always 0 if the index is out of range + std::int16_t get_child_y(std::uint16_t index) const; + + /// @brief Sets the X offset of the child object associated with the specified index into the parent object + /// @param[in] index The child index to affect + /// @param[in] xOffset The relative X position of the child, and always 0 if the index is out of range + void set_child_x(std::uint16_t index, std::int16_t xOffset); + + /// @brief Sets the Y offset of the child object associated with the specified index into the parent object + /// @param[in] index The child index to affect + /// @param[in] yOffset The relative Y position of the child, and always 0 if the index is out of range + void set_child_y(std::uint16_t index, std::int16_t yOffset); + + /// @brief Offsets all child objects with the specified ID by the amount specified relative to its parent + /// @param[in] childObjectID The object ID of the children to offset + /// @param[in] xOffset The relative amount to offset the object(s) by in the X axis + /// @param[in] yOffset The relative amount to offset the object(s) by in the Y axis + /// @returns true if any child matched the specified object ID, otherwise false if no children were found with the specified ID. + bool offset_all_children_with_id(std::uint16_t childObjectID, std::int8_t xOffset, std::int8_t yOffset); + + /// @brief Removes an object reference from another object. All fields must exactly match for the object to be removed. + /// This is because objects can have multiple of the same child at different places, so we can't infer which one to + /// remove without the exact position. + /// @param[in] objectIDToRemove The object ID of the child to remove + /// @param[in] relativeXLocation The X offset of this object to its parent + /// @param[in] relativeYLocation The Y offset of this object to its parent + void remove_child(std::uint16_t objectIDToRemove, std::int16_t relativeXLocation, std::int16_t relativeYLocation); + + /// @brief Removes the last added child object. + /// This is meant to be a faster way to deal with objects that only have a max of 1 child. + void pop_child(); + + /// @brief Returns the number of macros referenced by this object + /// @returns The number of macros referenced by this object + std::uint8_t get_number_macros() const; + + /// @brief Adds a macro to the list of macros referenced by this object + /// @param[in] macroToAdd The macro to add, which includes the event ID and macro ID + void add_macro(MacroMetadata macroToAdd); + + /// @brief Returns the macro ID at the specified index + /// @param[in] index The index of the macro to retrieve + /// @returns The macro metadata at the specified index, or NULL_OBJECT_ID + EventID::Reserved if the index is out of range + MacroMetadata get_macro(std::uint8_t index) const; + + /// @brief Returns a VT object from its member pool by ID, or the null id if it does not exist + /// @param[in] objectID The object ID to search for + /// @param[in] objectPool The object pool to search in + /// @returns The object with the corresponding ID + static std::shared_ptr get_object_by_id(std::uint16_t objectID, const std::map> &objectPool); + + protected: + /// @brief Storage for child object data + class ChildObjectData + { + public: + /// @brief Default constructor for child object data with default values + ChildObjectData() = default; + + /// @brief Constructor that initializes all members with parameters + /// @param[in] objectId The object ID of this child object + /// @param[in] x The x location of this child relative to the parent object + /// @param[in] y The y location of this child relative to the parent object + ChildObjectData(std::uint16_t objectId, + std::int16_t x, + std::int16_t y); + std::uint16_t id = NULL_OBJECT_ID; ///< Object identifier. Shall be unique within the object pool. + std::int16_t xLocation = 0; ///< Relative X location of the top left corner of the object + std::int16_t yLocation = 0; ///< Relative Y location of the top left corner of the object + }; + + std::vector children; ///< List of child objects + std::vector macros; ///< List of macros referenced by this object + std::uint16_t objectID = NULL_OBJECT_ID; ///< Object identifier. Shall be unique within the object pool. + std::uint16_t width = 0; ///< The width of the object. Not always applicable, but often used. + std::uint16_t height = 0; ///< The height of the object. Not always applicable, but often used. + std::uint8_t backgroundColor = 0; ///< The background color (from the VT colour table) + }; + + /// @brief This object shall include one or more objects that fit inside a Soft Key designator for use as an + /// identification of the Working Set. + class WorkingSet : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + Selectable = 2, + ActiveMask = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Constructor for a working set object + WorkingSet() = default; + + /// @brief Virtual destructor for a working set object + ~WorkingSet() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating this object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns if the working set is currently selectable + /// @returns `true` if the working set is currently selectable, otherwise false + bool get_selectable() const; + + /// @brief Sets if the working set is selectable + /// @param[in] value `true` to make the working set selectable, otherwise false + void set_selectable(bool value); + + /// @brief Returns tha currently active mask for this working set + /// @returns The object ID of the active mask for this working set + std::uint16_t get_active_mask() const; + + /// @brief Sets the object id of the active mask for this working set + /// @param[in] value The object ID of the active mask for this working set + void set_active_mask(std::uint16_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 18; ///< The fewest bytes of IOP data that can represent this object + + std::vector languageCodes; ///< A list of 2 character language codes, like "en" + std::uint16_t activeMask = NULL_OBJECT_ID; ///< The currently active mask for this working set + bool selectable = false; ///< If this working set is selectable right now + }; + + /// @brief The Data Mask describes the objects that will appear in the Data Mask area of the physical display. + class DataMask : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + SoftKeyMask = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Constructor for a data mask object + DataMask() = default; + + /// @brief Virtual destructor for a data mask object + ~DataMask() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Changes the soft key mask associated to this data mask to a new object ID. + /// Performs error checking on the type of the assigned object to ensure it is a soft key mask. + /// @param[in] newMaskID The object ID of the new soft key mask to associate with this data mask + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @returns True if the mask was changed, false if the new ID was not valid and the mask was not changed + bool change_soft_key_mask(std::uint16_t newMaskID, const std::map> &objectPool); + + /// @brief Changes the soft key mask associated to this data mask to a new object ID, but + /// does no checking on the validity of the new object ID. + /// @param[in] newMaskID The object ID of the new soft key mask to associate with this data mask + void set_soft_key_mask(std::uint16_t newMaskID); + + /// @brief Returns the object ID of the soft key mask associated with this data mask + /// @returns The object ID of the soft key mask associated with this data mask + std::uint16_t get_soft_key_mask() const; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 12; ///< The fewest bytes of IOP data that can represent this object + std::uint16_t softKeyMaskObjectID = NULL_OBJECT_ID; ///< The object ID of the soft key mask associated with this data mask + }; + + /// @brief Similar to a data mask, but takes priority and will be shown over data masks. + class AlarmMask : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + SoftKeyMask = 2, + Priority = 3, + AcousticSignal = 4, + + NumberOfAttributes = 5 + }; + + /// @brief Enumerates the different mask priorities. Higher priority masks will be shown over lower priority ones across all working sets. + enum class Priority : std::uint8_t + { + High = 0, ///< High, operator is in danger or urgent machine malfunction + Medium = 1, ///< Medium, normal alarm, machine is malfunctioning + Low = 2 ///< Low, information only + }; + + /// @brief Enumerates the acoustic signal values for the alarm mask. Works only if your VT has a way to make sounds. + /// @details The result of this setting is somewhat proprietary depending on your VT + enum class AcousticSignal : std::uint8_t + { + Highest = 0, ///< Most aggressive beeping + Medium = 1, ///< Medium beeping + Lowest = 3, ///< Low beeping + None = 4 ///< No beeping + }; + + /// @brief Constructor for a alarm mask object + AlarmMask() = default; + + /// @brief Virtual destructor for a alarm mask object + ~AlarmMask() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the priority of the alarm mask + /// @details Higher priority masks will be shown over lower priority ones. + /// @returns The priority of the alarm mask + Priority get_mask_priority() const; + + /// @brief Sets the priority of the alarm mask. + /// @details Higher priority masks will be shown over lower priority ones. + /// @param[in] value The priority to set + void set_mask_priority(Priority value); + + /// @brief Returns the acoustic signal priority for the alarm mask. + /// @details Controls how aggressive the beep is on VTs with a speaker or whistle chip. + /// @returns The acoustic signal priority of the alarm mask + AcousticSignal get_signal_priority() const; + + /// @brief Sets the acoustic signal priority for the alarm mask + /// @details Controls how aggressive the beep is on VTs with a speaker or whistle chip. + /// @param value The acoustic signal priority to set + void set_signal_priority(AcousticSignal value); + + /// @brief Changes the soft key mask associated to this alarm mask to a new object ID. + /// Performs error checking on the type of the assigned object to ensure it is a soft key mask. + /// @param[in] newMaskID The object ID of the new soft key mask to associate with this data mask + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @returns True if the mask was changed, false if the new ID was not valid and the mask was not changed + bool change_soft_key_mask(std::uint16_t newMaskID, const std::map> &objectPool); + + /// @brief Changes the soft key mask associated to this alarm mask to a new object ID, but + /// does no checking on the validity of the new object ID. + /// @param[in] newMaskID The object ID of the new soft key mask to associate with this alarm mask + void set_soft_key_mask(std::uint16_t newMaskID); + + /// @brief Returns the object ID of the soft key mask associated with this alarm mask + /// @returns The object ID of the soft key mask associated with this alarm mask + std::uint16_t get_soft_key_mask() const; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 10; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t softKeyMask = NULL_OBJECT_ID; ///< Object ID of a soft key mask for this alarm mask, or the null ID + Priority maskPriority = Priority::High; ///< The priority of this mask + AcousticSignal signalPriority = AcousticSignal::Highest; ///< The acoustic signal priority for this mask + }; + + /// @brief The Container object is used to group objects for the purpose of moving, hiding or sharing the group. + /// @details A container is not a visible object, only a logical grouping of other objects. Unlike masks, containers can be + /// hidden and shown at run-time + class Container : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + Hidden = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Constructor for a container object + Container() = default; + + /// @brief Virtual destructor for a container object + ~Container() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the "hidden" attribute for this container + /// @returns true if the hidden attribute is set, otherwise `false` + bool get_hidden() const; + + /// @brief Sets the "hidden" attribute for this container + /// @param[in] value The new attribute state + void set_hidden(bool value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 9; ///< The fewest bytes of IOP data that can represent this object + + bool hidden = false; ///< The hidden attribute state for this container object. True means it will be hidden when rendered. + }; + + /// @brief The Soft Key Mask is a Container object that contains Key objects, Object Pointer objects, or External Object + /// Pointer objects. + /// @details Keys are assigned to physical Soft Keys in the order listed. It is allowable for a Soft Key Mask to + /// contain no Keys in order that all Soft Keys are effectively disabled when this mask is activated + class SoftKeyMask : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + + NumberOfAttributes = 2 + }; + + /// @brief Constructor for a soft key mask object + SoftKeyMask() = default; + + /// @brief Virtual destructor for a soft key mask object + ~SoftKeyMask() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 6; ///< The fewest bytes of IOP data that can represent this object + }; + + /// @brief The Key object defines the designator and key code for a Soft Key. Any object located outside of a Soft Key + /// designator is clipped. + class Key : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + KeyCode = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Constructor for a key object + Key() = default; + + /// @brief Virtual destructor for a key object + ~Key() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the key code associated to this key object + /// @returns The key code associated to this key object + std::uint8_t get_key_code() const; + + /// @brief Sets the key code associated to this key object + /// @param[in] value The key code to set + void set_key_code(std::uint8_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 7; ///< The fewest bytes of IOP data that can represent this object + + std::uint8_t keyCode = 0; ///< They key code associated with events from this key object + }; + + /// @brief The Key objects contained in this object shall be a grouping of Key objects, or Object Pointers to Key objects + class KeyGroup : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Options = 1, + Name = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Enumerates the options bits in the options bitfield of a KeyGroup + enum class Options : std::uint8_t + { + Available = 0, ///< If 0 (FALSE) this object is not available for use at the present time, even though defined + Transparent = 1 ///< If this bit is 1, the VT shall ignore the background colour attribute in all child Key objects + }; + + /// @brief Constructor for a key group object + KeyGroup() = default; + + /// @brief Virtual destructor for a key group object + ~KeyGroup() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the key group icon that represents this key group + /// @returns Object ID of the key group icon that represents this key group + std::uint16_t get_key_group_icon() const; + + /// @brief Sets the object ID of the icon to use when representing this key group + /// @param[in] value Object ID of a picture graphic to use as the key group icon + void set_key_group_icon(std::uint16_t value); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + /// @brief Sets the Object ID of an Output String object or an Object Pointer object + /// that points to an Output String object that contains a name for this object + /// @returns Object ID of an Output String object or an Object Pointer object that will represent the name of this key group + std::uint16_t get_name_object_id() const; + + /// @brief Sets the Object ID of an Output String object or an Object Pointer object + /// that points to an Output String object that contains a name for this object + /// @param[in] value The object ID of the object that will represent the name of this key group, CANNOT BE the null object ID + void set_name_object_id(std::uint16_t value); + + static constexpr std::uint8_t MAX_CHILD_KEYS = 4; ///< There shall be a max of 4 keys per group according to the standard + + private: + /// @brief Validates that the specified name ID is valid for this object + /// @param[in] nameIDToValidate The name's object ID to validate + /// @param[in] objectPool The object pool to use when validating the name object + /// @returns True if the name ID is valid for this object, otherwise false + bool validate_name(std::uint16_t nameIDToValidate, const std::map> &objectPool) const; + + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 10; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t keyGroupIcon = NULL_OBJECT_ID; ///< The VT may use this in the proprietary mapping screen to represent the key group + std::uint16_t nameID = NULL_OBJECT_ID; ///< Object ID of a string variable that contains the name of the key group + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + }; + + /// @brief The Button object defines a button control. + /// @details This object is intended mainly for VTs with touch screens or a + /// pointing method but shall be supported by all VTs. + class Button : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + BackgroundColour = 3, + BorderColour = 4, + KeyCode = 5, + Options = 6, // Version 4 and later + + NumberOfAttributes = 7 + }; + + /// @brief Enumerates the options encoded into the options bitfield for a button + enum class Options : std::uint8_t + { + Latchable = 0, ///< If TRUE, the Button is latchable and remains pressed until the next activation. If FALSE, the Button is momentary. + CurrentButtonStateIfLatchable = 1, ///< For latchable Buttons. 0=released, 1=latched + SuppressBorder = 2, ///< If FALSE, VT draws the proprietary border. If TRUE, no border is ever drawn + TransparentBackground = 3, ///< If FALSE, the Button's interior background is filled using the background colour attribute. If TRUE, the Button's background is always transparent + Disabled = 4, ///< If FALSE, the Button is enabled and can be selected and activated by the operator. If TRUE, the Button is drawn disabled (method proprietary) + NoBorder = 5, ///< If FALSE, the Button Border area is used by the VT as described in Bit 2. If TRUE, Bit 2 is ignored therefore no border is ever drawn and the Button Face extends to the full Button Area + Reserved1 = 6, ///< Set to 0 + Reserved2 = 7 ///< Set to 0 + }; + + /// @brief Constructor for a button object + Button() = default; + + /// @brief Virtual destructor for a button object + ~Button() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the key code associated with this button's events + /// @returns The key code associated with this button's events + std::uint8_t get_key_code() const; + + /// @brief Sets the key code associated with this button's events + /// @param[in] value The key code to set + void set_key_code(std::uint8_t value); + + /// @brief Returns the colour of the button's border as an index into the VT colour table + /// @returns The colour of the button's border as an index into the VT colour table + std::uint8_t get_border_colour() const; + + /// @brief Sets the border colour + /// @param[in] value The border colour to set as an index into the VT colour table + void set_border_colour(std::uint8_t value); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 13; ///< The fewest bytes of IOP data that can represent this object + + std::uint8_t borderColour = 0; ///< Border colour. + std::uint8_t keyCode = 0; ///< Key code assigned by ECU. VT reports this code in the Button Activation message. + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + }; + + /// @brief The Input Boolean object is used to input a TRUE/FALSE type indication from the operator + class InputBoolean : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + Width = 2, + ForegroundColour = 3, + VariableReference = 4, + Value = 5, + Enabled = 6, // Version 4 and later + + NumberOfAttributes = 7 + }; + + /// @brief Constructor for an input boolean object + InputBoolean() = default; + + /// @brief Virtual destructor for an input boolean object + ~InputBoolean() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the value of the boolean (only matters if a reference object is not present) + /// @note The reference object will be a child number variable object if it is present + /// @returns The value of the boolean object + std::uint8_t get_value() const; + + /// @brief Sets the value of the boolean object (only matters if a reference object is not present) + /// @note The reference object will be a child number variable object if it is present + /// @param[in] inputValue The value to set for the boolean's state + void set_value(std::uint8_t inputValue); + + /// @brief Returns if this object is enabled based on the enabled attribute + /// @returns `true` If the enabled attribute on this object is `true`, otherwise `false` + bool get_enabled() const; + + /// @brief Sets the enabled attribute on this object to a new value + /// @param[in] isEnabled The new state for the enabled attribute for this object + void set_enabled(bool isEnabled); + + /// @brief Returns the object ID of a font attributes object that defines the foreground colour, or the null ID + /// @returns The object ID of a font attributes object that defines the foreground colour, or the null ID + std::uint16_t get_foreground_colour_object_id() const; + + /// @brief Sets the object ID of the foreground colour object. + /// Does not perform error checking on the type of the supplied object. + /// @param[in] fontAttributeValue The object ID of the foreground colour object + void set_foreground_colour_object_id(std::uint16_t fontAttributeValue); + + /// @brief Returns the object ID of a number variable object that contains the value of the Input Boolean object + /// or the null ID if the "value" attribute is used instead. + /// @returns The object ID of a number variable object that contains the value of the Input Boolean object, or the null ID + std::uint16_t get_variable_reference() const; + + /// @brief Sets the object ID of the number variable object that contains the value of the Input Boolean object. + /// Does no error checking on the type of the supplied object. + /// @param[in] numberVariableValue The object ID of the number variable object that contains the value of the Input Boolean object, or the null ID + void set_variable_reference(std::uint16_t numberVariableValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 13; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t foregroundColourObjectID = NULL_OBJECT_ID; ///< Object ID of a font attributes that contains the foreground colour of the Input Boolean object + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Object ID of a number variable object that contains the value of the Input Boolean object + std::uint8_t value = 0; ///< Used only if it has no number variable child object + bool enabled = false; ///< If the bool is interactable + }; + + /// @brief This object is used to input a character string from the operator + class InputString : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + BackgroundColour = 3, + FontAttributes = 4, + InputAttributes = 5, + Options = 6, + VariableReference = 7, + Justification = 8, + Enabled = 9, // Version 4 and later + + NumberOfAttributes = 10 + }; + + /// @brief Options that can be applied to the input string + enum class Options : std::uint8_t + { + Transparent = 0, ///< If TRUE, the input field is displayed with background showing through instead of using the background colour + AutoWrap = 1, ///< Auto-Wrapping rules apply + WrapOnHyphen = 2 ///< If TRUE, Auto-Wrapping can occur between a hyphen and the following character. + }; + + /// @brief The allowable horizontal justification options + enum class HorizontalJustification : std::uint8_t + { + PositionLeft = 0, ///< The input string is horizontally justified to the left side of its bounding box + PositionMiddle = 1, ///< The input string is horizontally justified to the center of its bounding box + PositionRight = 2, ///< The input string is horizontally justified to the right side of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief The allowable vertical justification options + enum class VerticalJustification : std::uint8_t + { + PositionTop = 0, ///< The input string is vertically justified to the top of its bounding box + PositionMiddle = 1, ///< The input string is vertically justified to the center of its bounding box + PositionBottom = 2, ///< The input string is vertically justified to the bottom of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief Constructor for a input string object + InputString() = default; + + /// @brief Virtual destructor for a input string object + ~InputString() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns if the input string is enabled for text entry + /// @returns `true` if the input string is enabled for entry + bool get_enabled() const; + + /// @brief Sets the enable/disable state of the input string + /// @param[in] value The new enable/disable state for the input string + void set_enabled(bool value); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + /// @brief Returns the horizontal justification setting of the string + /// @returns The horizontal justification setting of the string + HorizontalJustification get_horizontal_justification() const; + + /// @brief Returns the vertical justification setting of the string + /// @returns The vertical justification setting of the string + VerticalJustification get_vertical_justification() const; + + /// @brief Sets the justification bitfield of the string + /// @param[in] value The justification bitfield to set + void set_justification_bitfield(std::uint8_t value); + + /// @brief Returns a copy of the stored string value. Used only when no string + /// variable objects are children of this object. + /// @returns The value of the string stored in this object + std::string get_value() const; + + /// @brief Changes the stored string value. Use only when no + /// string variable objects are children of this object. + /// @param[in] value The new string value + void set_value(const std::string &value); + + /// @brief Returns the object ID of a font attributes object that defines the font attributes of the Input String object + /// @returns The object ID of a font attributes object that defines the font attributes of the Input String object + std::uint16_t get_font_attributes() const; + + /// @brief Sets the object ID of a font attributes object that defines the font attributes of the Input String object. + /// Does no error checking on the type of the supplied object. + /// @param[in] fontAttributesValue The object ID of a font attributes object that defines the font attributes of the Input String object + void set_font_attributes(std::uint16_t fontAttributesValue); + + /// @brief Returns the object ID of a string variable object that contains the value of the Input String object + /// @returns The object ID of a string variable object that contains the value of the Input String object + std::uint16_t get_variable_reference() const; + + /// @brief Sets the object ID of a string variable object that contains the value of the Input String object. + /// Does no error checking on the type of the supplied object. + /// @param[in] variableReferenceValue The object ID of a string variable object that contains the value of the Input String object + void set_variable_reference(std::uint16_t variableReferenceValue); + + /// @brief Returns the object ID of a input attributes object that defines what can be input into the Input String object. + /// @returns The object ID of a input attributes object that defines the input attributes of the Input String object + std::uint16_t get_input_attributes() const; + + /// @brief Sets the object ID of a input attributes object that defines what can be input into the Input String object. + /// Does no error checking on the type of the supplied object. + /// @param[in] inputAttributesValue The object ID of a input attributes object that defines the input attributes of the Input String object + void set_input_attributes(std::uint16_t inputAttributesValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 19; ///< The fewest bytes of IOP data that can represent this object + + std::string stringValue; ///< The actual string. Used only if variable reference attribute is NULL. Pad with spaces as necessary to satisfy length attribute. + std::uint16_t fontAttributes = NULL_OBJECT_ID; ///< Stores the object ID of a font attributes object that will be used to display this object. + std::uint16_t inputAttributes = NULL_OBJECT_ID; ///< Stores the object ID of a input attributes object that will be used to determine what can be input into this object. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Stores the object ID of a string variable object that will be used in place of the string value attribute if it is not NULL_OBJECT_ID. + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t justificationBitfield = 0; ///< Bitfield of justification options + bool enabled = false; ///< If the string is interactable + }; + + /// @brief This object is used to format, display and change a numeric value based on a supplied integer value. + /// @details Displayed value = (value attribute + Offset) * Scaling Factor + class InputNumber : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + BackgroundColour = 3, + FontAttributes = 4, + Options = 5, + VariableReference = 6, + MinValue = 7, + MaxValue = 8, + Offset = 9, + Scale = 10, + NumberOfDecimals = 11, + Format = 12, + Justification = 13, + Value = 14, + Options2 = 15, // Version 4 and after + + NumberOfAttributes = 16 + }; + + /// @brief Options that can be applied to the input number + enum class Options : std::uint8_t + { + Transparent = 0, ///< If TRUE, the input field is displayed with background showing through instead of using the background colour + DisplayLeadingZeros = 1, ///< If TRUE, fill left to width of field with zeros; justification is applied after filling + DisplayZeroAsBlank = 2, ///< When this option bit is set, a blank field is displayed if and only if the displayed value of the object is exactly zero + Truncate = 3 ///< If TRUE the value shall be truncated to the specified number of decimals. Otherwise it shall be rounded off to the specified number of decimals. + }; + + /// @brief More options, for some reason they are different bytes + enum class Options2 : std::uint8_t + { + Enabled = 0, ///< If TRUE the object shall be enabled + RealTimeEditing = 1 ///< If TRUE the value shall be transmitted to the ECU as it is being changed + }; + + /// @brief The allowable horizontal justification options + enum class HorizontalJustification : std::uint8_t + { + PositionLeft = 0, ///< The input number is horizontally justified to the left side of its bounding box + PositionMiddle = 1, ///< The input number is horizontally justified to the center of its bounding box + PositionRight = 2, ///< The input number is horizontally justified to the right side of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief The allowable vertical justification options + enum class VerticalJustification : std::uint8_t + { + PositionTop = 0, ///< The input number is vertically justified to the top of its bounding box + PositionMiddle = 1, ///< The input number is vertically justified to the center of its bounding box + PositionBottom = 2, ///< The input number is vertically justified to the bottom of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief Constructor for an input number object + InputNumber() = default; + + /// @brief Virtual destructor for an input number object + ~InputNumber() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the horizontal justification setting of the input number + /// @returns The horizontal justification setting of the input number + HorizontalJustification get_horizontal_justification() const; + + /// @brief Returns the vertical justification setting of the input number + /// @returns The vertical justification setting of the input number + VerticalJustification get_vertical_justification() const; + + /// @brief Sets the justification bitfield of the input number + /// @param[in] newJustification The justification bitfield to set + void set_justification_bitfield(std::uint8_t newJustification); + + /// @brief Returns the scale factor that is applied to the value of the input number + /// @returns The scale factor that is applied to the value of the input number + float get_scale() const; + + /// @brief Sets the scale factor that is applied to the value of the input number + /// @param[in] newScale The scale factor to set + void set_scale(float newScale); + + /// @brief Returns the maximum value for the input number + /// @details The VT shall not accept values higher than this for this input number's value + /// @returns The maximum value for the input number + std::uint32_t get_maximum_value() const; + + /// @brief Sets the maximum value for the input number + /// @details The VT shall not accept values higher than this for this input number's value + /// @param[in] newMax The maximum value for the input number + void set_maximum_value(std::uint32_t newMax); + + /// @brief Returns the minimum value for this input number + /// @details The VT shall not accept values smaller than this value for this input number + /// @returns The minimum value for this input number + std::uint32_t get_minimum_value() const; + + /// @brief Sets the minimum value for the input number + /// @details The VT shall not accept values smaller than this value for this input number + /// @param[in] newMin The minimum value to set for the input number + void set_minimum_value(std::uint32_t newMin); + + /// @brief Returns the offset that will be applied to the number's value when it is displayed + /// @returns The offset that will be applied to the number's value when it is displayed + std::int32_t get_offset() const; + + /// @brief Sets the offset that will be applied to the number's value when it is displayed + /// @param[in] newOffset The new offset that will be applied to the number's value when it is displayed + void set_offset(std::int32_t newOffset); + + /// @brief Returns the number of decimals to display when rendering this input number + /// @returns The number of decimals to display when rendering the input number + std::uint8_t get_number_of_decimals() const; + + /// @brief Sets the number of decimals to display when rendering this number + /// @param[in] numDecimals The number of decimals to display + void set_number_of_decimals(std::uint8_t numDecimals); + + /// @brief Returns if the format option is set for this input number + /// @details The format option determines if the value is shown in fixed decimal or exponential form. + /// A value of `true` means fixed decimal (####.nn), and `false` means exponential ([−]###.nnE[+/−]##) + /// @returns `true` if the format option is set for this input number, otherwise `false` + bool get_format() const; + + /// @brief Sets the format option + /// @details The format option determines if the value is shown in fixed decimal or exponential form. + /// A value of `true` means fixed decimal (####.nn), and `false` means exponential ([−]###.nnE[+/−]##) + /// @param[in] newFormat The format value to set. `true` for fixed decimal, false for exponential. + void set_format(bool newFormat); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] newOptions The new value for the options bitfield + void set_options(std::uint8_t newOptions); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] optionValue The new value of the option bit + void set_option(Options option, bool optionValue); + + /// @brief Returns the state of a single option in the object's second option bitfield + /// @param[in] newOption The option to check the value of in the object's second option bitfield + /// @returns The state of the associated option bit + bool get_option2(Options2 newOption) const; + + /// @brief Sets the second options bitfield for this object to a new value + /// @param[in] newOptions The new value for the second options bitfield + void set_options2(std::uint8_t newOptions); + + /// @brief Sets a single option in the second options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] newOption The new value of the option bit + void set_option2(Options2 option, bool newOption); + + /// @brief Returns the value of the input number (only matters if there's no child number variable object). + /// @returns The value of the input number + std::uint32_t get_value() const; + + /// @brief Sets the value of the input number (only matters if there's no child number variable object). + /// @param[in] inputValue The value to set for the input number + void set_value(std::uint32_t inputValue); + + /// @brief Returns the object ID of a font attributes object that defines the font attributes of the Input Number object + /// @returns The object ID of a font attributes object that defines the font attributes of the Input Number object + std::uint16_t get_font_attributes() const; + + /// @brief Sets the object ID of a font attributes object that defines the font attributes of the Input Number object. + /// Does no error checking on the type of the supplied object. + /// @param[in] fontAttributesValue The object ID of a font attributes object that defines the font attributes of the Input Number object + void set_font_attributes(std::uint16_t fontAttributesValue); + + /// @brief Returns the object ID of a number variable object that contains the value of the Input Number object + /// @returns The object ID of a number variable object that contains the value of the Input Number object + std::uint16_t get_variable_reference() const; + + /// @brief Sets the object ID of a number variable object that contains the value of the Input Number object. + /// Does no error checking on the type of the supplied object. + /// @param[in] variableReferenceValue The object ID of a number variable object that contains the value of the Input Number object + void set_variable_reference(std::uint16_t variableReferenceValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 38; ///< The fewest bytes of IOP data that can represent this object + + float scale = 0.0f; ///< Scale to be applied to the input value and min/max values. + std::uint32_t maximumValue = 0; ///< Raw maximum value for the input + std::uint32_t minimumValue = 0; ///< Raw minimum value for the input before scaling + std::uint32_t value = 0; ///< The raw value of the object, used if no number variable child has been set + std::int32_t offset = 0; ///< Offset to be applied to the input value and min/max values + std::uint16_t fontAttributes = NULL_OBJECT_ID; ///< Stores the object ID of a font attributes object that will be used to display this object. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Stores the object ID of a number variable object that will be used in place of the value attribute if it is not NULL_OBJECT_ID. + std::uint8_t numberOfDecimals = 0; ///< Specifies number of decimals to display after the decimal point + std::uint8_t options = 0; ///< Options byte 1 + std::uint8_t options2 = 0; ///< Options byte 2 + std::uint8_t justificationBitfield = 0; ///< Indicates how the number is positioned in the field defined by height and width + bool format = false; ///< 0 = use fixed format decimal display (####.nn), 1 = use exponential format ([-]###.nnE[+/-]##) where n is set by the number of decimals + }; + + /// @brief The Input List object is used to show one object out of a set of objects, + /// and to allow operator selection of one object from the set. + class InputList : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + VariableReference = 3, + Value = 4, + Options = 5, // Version 4 and after + + NumberOfAttributes = 6 + }; + + /// @brief Enumerates the bits in the options bitfield for an InputList + enum class Options + { + Enabled = 0, ///< If true the object shall be enabled + RealTimeEditing = 1 ///< If true the value shall be transmitted to the ECU as it is being changed + }; + + /// @brief Constructor for an input list object + InputList() = default; + + /// @brief Virtual destructor for an input list object + ~InputList() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] options The new value for the options bitfield + void set_options(std::uint8_t options); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] optionValue The new value of the option bit + void set_option(Options option, bool optionValue); + + /// @brief Returns the value of the selected list index (only matters if there is no child number variable) + /// @returns The value of the selected list index + std::uint8_t get_value() const; + + /// @brief Sets the selected list index (only matters when the object has no child number variable) + /// @param[in] inputValue The new value for the selected list index + void set_value(std::uint8_t inputValue); + + /// @brief A dedicated way to set the stored variable reference so we don't have + /// to worry about the child object list getting messed up from changing the attribute + /// or a list item. + /// @param[in] referencedObjectID The object ID of a number variable to set as the value reference + void set_variable_reference(std::uint16_t referencedObjectID); + + /// @brief Returns the variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + /// @returns The variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + std::uint16_t get_variable_reference() const; + + /// @brief Changes a list item to a new ID by index + /// @param[in] index The index to change (starting from 0) + /// @param[in] newListItem The object ID to use as the new list item at the specified index + /// @param[in] objectPool The object pool to use to look up the object ID + /// @returns True if the operation was successful, otherwise false (perhaps the index is out of bounds?) + bool change_list_item(std::uint8_t index, std::uint16_t newListItem, const std::map> &objectPool); + + /// @brief Returns the number of items in the list + /// @note This is not the number of children, it's the number of allocated + /// list items. The number of children can be less than this number. + /// @returns The number of items in the list + std::uint8_t get_number_of_list_items() const; + + /// @brief Sets the number of items in the list + /// @note This is not the number of children, it's the number of allocated + /// list items. The number of children can be less than this number. + /// @param[in] value The number of items in the list + void set_number_of_list_items(std::uint8_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 13; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Stores the object ID of a number variable that will be used as the value, or the NULL_OBJECT_ID if not used. + std::uint8_t numberOfListItems = 0; ///< Number of object references to follow. The size of the list can never exceed this number and this attribute cannot be changed. + std::uint8_t optionsBitfield = 0; ///< Options byte + std::uint8_t value = 0; ///< Selected list index of this object. Used only if variable reference attribute is NULL + }; + + /// @brief This object is used to output a string of text + class OutputString : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + BackgroundColour = 3, + FontAttributes = 4, + Options = 5, + VariableReference = 6, + Justification = 7, + + NumberOfAttributes = 8 + }; + + /// @brief Enumerates the option bits in the options bitfield for an output string + enum class Options + { + Transparent = 0, ///< If TRUE, the output field is displayed with background showing through instead of using the background colour + AutoWrap = 1, ///< Auto-Wrapping rules apply + WrapOnHyphen = 2 ///< If TRUE, Auto-Wrapping can occur between a hyphen and the next character + }; + + /// @brief The allowable horizontal justification options + enum class HorizontalJustification : std::uint8_t + { + PositionLeft = 0, ///< Output string is horizontally aligned to the left of its bounding box + PositionMiddle = 1, ///< Output string is horizontally aligned to the center of its bounding box + PositionRight = 2, ///< Output string is horizontally aligned to the right of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief The allowable vertical justification options + enum class VerticalJustification : std::uint8_t + { + PositionTop = 0, ///< Output string is vertically aligned to the top of its bounding box + PositionMiddle = 1, ///< Output string is vertically aligned to the center of its bounding box + PositionBottom = 2, ///< Output string is vertically aligned to the bottom of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief Constructor for an output string object + OutputString() = default; + + /// @brief Virtual destructor for an output string object + ~OutputString() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + /// @brief Returns the horizontal justification of the output string within its bounding box + /// @returns The horizontal justification of the output string within its bounding box + HorizontalJustification get_horizontal_justification() const; + + /// @brief Returns the vertical justification of the output string within its bounding box + /// @returns The vertical justification of the output string within its bounding box + VerticalJustification get_vertical_justification() const; + + /// @brief Sets the justification bitfield for the object to a new value + /// @param[in] value The new value for the justification bitfield + void set_justification_bitfield(std::uint8_t value); + + /// @brief Returns the value of the string, used only if the variable reference (a child var string) is NULL_OBJECT_ID + /// @returns The value of the string + std::string get_value() const; + + /// @brief Sets the value of the string (only matters if it has no child string variable) + /// @param[in] value The new value for the string + void set_value(const std::string &value); + + /// @brief Returns the object ID of a font attributes object that defines the font attributes of the Output String object + /// @returns The object ID of a font attributes object that defines the font attributes of the Output String object + std::uint16_t get_font_attributes() const; + + /// @brief Sets the object ID of a font attributes object that defines the font attributes of the Output String object. + /// Does no error checking on the type of the supplied object. + /// @param[in] fontAttributesValue The object ID of a font attributes object that defines the font attributes of the Output String object + void set_font_attributes(std::uint16_t fontAttributesValue); + + /// @brief Returns the object ID of a string variable object that contains the value of the Output String object + /// @returns The object ID of a string variable object that contains the value of the Output String object + std::uint16_t get_variable_reference() const; + + /// @brief Sets the object ID of a string variable object that contains the value of the Output String object. + /// Does no error checking on the type of the supplied object. + /// @param[in] variableReferenceValue The object ID of a string variable object that contains the value of the Output String object + void set_variable_reference(std::uint16_t variableReferenceValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 16; ///< The fewest bytes of IOP data that can represent this object + + std::string stringValue; ///< The actual string. Used only if variable reference attribute is NULL. Pad with spaces as necessary to satisfy length attribute. + std::uint16_t fontAttributes = NULL_OBJECT_ID; ///< Stores the object ID of a font attributes object that will be used to display this object. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Stores the object ID of a string variable object that will be used in place of the string value attribute if it is not NULL_OBJECT_ID. + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t justificationBitfield = 0; ///< Bitfield of justification options + }; + + /// @brief This object is used to format and output a numeric value based on a supplied integer value. + class OutputNumber : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + BackgroundColour = 3, + FontAttributes = 4, + Options = 5, + VariableReference = 6, + Offset = 7, + Scale = 8, + NumberOfDecimals = 9, + Format = 10, + Justification = 11, + + NumberOfAttributes = 12 + }; + + /// @brief Options that can be applied to the input number + enum class Options : std::uint8_t + { + Transparent = 0, ///< If true, the input field is displayed with background showing through instead of using the background colour + DisplayLeadingZeros = 1, ///< If true, fill left to width of field with zeros; justification is applied after filling + DisplayZeroAsBlank = 2, ///< When this option bit is set, a blank field is displayed if and only if the displayed value of the object is exactly zero + Truncate = 3 ///< If true the value shall be truncated to the specified number of decimals. Otherwise it shall be rounded off to the specified number of decimals. + }; + + /// @brief The allowable horizontal justification options + enum class HorizontalJustification : std::uint8_t + { + PositionLeft = 0, ///< The output number is horizontally justified to the left side of its bounding box + PositionMiddle = 1, ///< The output number is horizontally justified to the center of its bounding box + PositionRight = 2, ///< The output number is horizontally justified to the right side of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief The allowable vertical justification options + enum class VerticalJustification : std::uint8_t + { + PositionTop = 0, ///< The output number is vertically justified to the top of its bounding box + PositionMiddle = 1, ///< The output number is vertically justified to the center of its bounding box + PositionBottom = 2, ///< The output number is vertically justified to the bottom of its bounding box + Reserved = 3 ///< Reserved + }; + + /// @brief Constructor for an output number object + OutputNumber() = default; + + /// @brief Virtual destructor for an output number object + ~OutputNumber() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + /// @brief Returns the horizontal justification of the output number within its bounding box + /// @return The horizontal justification of the output number within its bounding box + HorizontalJustification get_horizontal_justification() const; + + /// @brief Returns the vertical justification of the output number within its bounding box + /// @return The vertical justification of the output number within its bounding box + VerticalJustification get_vertical_justification() const; + + /// @brief Sets the justification bitfield to a new value + /// @param[in] value The new value for the justification bitfield + void set_justification_bitfield(std::uint8_t value); + + /// @brief Returns the scale factor of the output number + /// @returns The scale factor of the output number + float get_scale() const; + + /// @brief Sets the scale factor for the output number + /// @param[in] scaleValue The new value for the scale factor + void set_scale(float scaleValue); + + /// @brief Returns the offset that is applied to the output number + /// @returns The offset of the output number + std::int32_t get_offset() const; + + /// @brief Sets the offset of the output number + /// @param[in] offsetValue The offset to set for the output number + void set_offset(std::int32_t offsetValue); + + /// @brief Returns the number of decimals to render in the output number + /// @returns The number of decimals to render in the output number + std::uint8_t get_number_of_decimals() const; + + /// @brief Sets the number of decimals to render in the output number + /// @param[in] decimalValue The number of decimals to render in the output number + void set_number_of_decimals(std::uint8_t decimalValue); + + /// @brief Returns if the "format" option is set for this object + /// @details The format option determines if fixed decimal or exponential notation is used. + /// A value of `false` is fixed decimal notation, and `true` is exponential notation + /// @returns `true` if the format option is set + bool get_format() const; + + /// @brief Sets the format option for this object. + /// @details The format option determines if fixed decimal or exponential notation is used. + /// A value of `false` is fixed decimal notation, and `true` is exponential notation + /// @param[in] shouldFormatAsExponential `true` to use fixed decimal notation (####.nn), `false` to use exponential ([−]###.nnE[+/−]##) + void set_format(bool shouldFormatAsExponential); + + /// @brief Returns the value of the output number (only matters if there's no child number variable object). + /// @returns The value of the output number. + std::uint32_t get_value() const; + + /// @brief Sets the value of the output number (only matters if there's no child number variable object). + /// @param[in] inputValue The value to set for the output number + void set_value(std::uint32_t inputValue); + + /// @brief A dedicated way to set the stored variable reference so we don't have + /// to worry about the child object list getting messed up from changing the attribute + /// or a list item. + /// @param[in] referencedObjectID The object ID of a number variable to set as the value reference + void set_variable_reference(std::uint16_t referencedObjectID); + + /// @brief Returns the variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + /// @returns The variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + std::uint16_t get_variable_reference() const; + + /// @brief Returns the object ID of a font attributes object that defines the font attributes of the Output Number object + /// @returns The object ID of a font attributes object that defines the font attributes of the Output Number object + std::uint16_t get_font_attributes() const; + + /// @brief Sets the object ID of a font attributes object that defines the font attributes of the Output Number object. + /// Does no error checking on the type of the supplied object. + /// @param[in] fontAttributesValue The object ID of a font attributes object that defines the font attributes of the Output Number object + void set_font_attributes(std::uint16_t fontAttributesValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 29; ///< The fewest bytes of IOP data that can represent this object + + float scale = 1.0f; ///< Scale to be applied to the input value and min/max values. + std::int32_t offset = 0; ///< Offset to be applied to the input value and min/max values + std::uint32_t value = 0; ///< Raw unsigned value of the output field before scaling (unsigned 32-bit integer). Used only if variable reference attribute is NULL + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Stores the object ID of a number variable that will be used as the value, or the NULL_OBJECT_ID if not used. + std::uint16_t fontAttributes = NULL_OBJECT_ID; ///< Stores the object ID of a font attributes object that will be used to display this object. + std::uint8_t numberOfDecimals = 0; ///< Specifies number of decimals to display after the decimal point + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t justificationBitfield = 0; ///< Bitfield of justification options + bool format = false; ///< 0 = use fixed format decimal display (####.nn), 1 = use exponential format ([-]###.nnE[+/-]##) where n is set by the number of decimals + }; + + /// @brief Used to show one object out of a set of objects + class OutputList : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + VariableReference = 3, + Value = 4, + + NumberOfAttributes = 5 + }; + + /// @brief Constructor for an output list object + OutputList() = default; + + /// @brief Virtual destructor for an output list object + ~OutputList() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the number of items in the list + /// @note This is not the number of children, it's the number of allocated + /// list items. The number of children can be less than this number. + /// @returns The number of items in the list + std::uint8_t get_number_of_list_items() const; + + /// @brief Sets the number of items in the list + /// @note This is not the number of children, it's the number of allocated + /// list items. The number of children can be less than this number. + /// @param[in] value The number of items in the list + void set_number_of_list_items(std::uint8_t value); + + /// @brief Returns the value of the selected list index (only matters if no child number variable object is present) + /// @returns The value of the selected list index + std::uint8_t get_value() const; + + /// @brief Sets the value of the selected list index (only matters if no child number variable object is present) + /// @param[in] value The value to set for the list's selected index + void set_value(std::uint8_t value); + + /// @brief A dedicated way to set the stored variable reference so we don't have + /// to worry about the child object list getting messed up from changing the attribute + /// or a list item. + /// @param[in] referencedObjectID The object ID of a number variable to set as the value reference + void set_variable_reference(std::uint16_t referencedObjectID); + + /// @brief Returns the variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + /// @returns The variable reference, which is an object ID of a number variable or NULL_OBJECT_ID (0xFFFF) + std::uint16_t get_variable_reference() const; + + /// @brief Changes a list item to a new ID by index + /// @param[in] index The index to change (starting from 0) + /// @param[in] newListItem The object ID to use as the new list item at the specified index + /// @param[in] objectPool The object pool to use to look up the object ID + /// @returns True if the operation was successful, otherwise false (perhaps the index is out of bounds?) + bool change_list_item(std::uint8_t index, std::uint16_t newListItem, const std::map> &objectPool); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 12; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t variableReference = NULL_OBJECT_ID; ///< The object ID of a number variable to use for the value/selected index, or NULL_OBJECT_ID + std::uint8_t numberOfListItems = 0; ///< Number of object references to follow. The size of the list can never exceed this number and this attribute cannot be changed. + std::uint8_t value = 0; ///< Selected list index of this object. Used only if variable reference attribute is NULL + }; + + /// @brief This object outputs a line shape. The starting point for the line is found in the parent object + class OutputLine : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + LineAttributes = 1, + Width = 2, + Height = 3, + LineDirection = 4, + + NumberOfAttributes = 5 + }; + + /// @brief Enumerates the different directions a line can be drawn + enum class LineDirection : std::uint8_t + { + TopLeftToBottomRight = 0, + BottomLeftToTopRight = 1 + }; + + /// @brief Constructor for an output line object + OutputLine() = default; + + /// @brief Virtual destructor for an output line object + ~OutputLine() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the line's direction. + /// @details When the line direction is zero, the ine is drawn from top left to bottom right of + /// enclosing virtual rectangle. When the line direction is 1, the line is drawn from bottom left to top right of + /// enclosing virtual rectangle. + /// @returns The line's direction (see details). + LineDirection get_line_direction() const; + + /// @brief Sets the line's direction. + /// @details When the line direction is zero, the ine is drawn from top left to bottom right of + /// enclosing virtual rectangle. When the line direction is 1, the line is drawn from bottom left to top right of + /// enclosing virtual rectangle. + /// @param[in] value The line direction to set (see details). + void set_line_direction(LineDirection value); + + /// @brief Returns the object ID of the line attributes used to display this line + /// @returns The object ID of the line attributes used to display this line + std::uint16_t get_line_attributes() const; + + /// @brief Sets the object ID of the line attributes used to display this line. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] lineAttributesObject The object ID of the line attributes used to display this line + void set_line_attributes(std::uint16_t lineAttributesObject); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 11; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t lineAttributes = NULL_OBJECT_ID; ///< Object ID of line attributes used to display this line + std::uint8_t lineDirection = 0; ///< 0 = Line is drawn from top left to bottom right of enclosing virtual rectangle, 1 = Line is drawn from bottom left to top right + }; + + /// @brief This object outputs a rectangle shape + class OutputRectangle : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + LineAttributes = 1, + Width = 2, + Height = 3, + LineSuppression = 4, + FillAttributes = 5, + + NumberOfAttributes = 6 + }; + /// @brief The different line suppression options + enum class LineSuppressionOption + { + SuppressTopLine = 0, ///< Suppress the top line of the rectangle + SuppressRightSideLine = 1, ///< Suppress the right side of the rectangle + SuppressBottomLine = 2, ///< Suppress the bottom line of the rectangle + SuppressLeftSideLine = 3 ///< Suppress the left line of the rectangle + }; + + /// @brief Constructor for an output rectangle object + OutputRectangle() = default; + + /// @brief Virtual destructor for an output rectangle object + ~OutputRectangle() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the line suppression bitfield. + /// @note See LineSuppressionOption for the bit definitions. + /// @returns The line suppression bitfield (see LineSuppressionOption). + std::uint8_t get_line_suppression_bitfield() const; + + /// @brief Sets the line suppression bitfield value. + /// @note See LineSuppressionOption for the bit definitions. + /// @param[in] value The line suppression bitfield to set. + void set_line_suppression_bitfield(std::uint8_t value); + + /// @brief Returns the object ID of the line attributes used to display this rectangle's lines + /// @returns The object ID of the line attributes used to display this rectangle's lines + std::uint16_t get_line_attributes() const; + + /// @brief Sets the object ID of the line attributes used to display this rectangle's lines. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] lineAttributesObject The object ID of the line attributes used to display this rectangle's lines + void set_line_attributes(std::uint16_t lineAttributesObject); + + /// @brief Returns the object ID of the fill attributes used to display this rectangle's fill + /// @returns The object ID of the fill attributes used to display this rectangle's fill + std::uint16_t get_fill_attributes() const; + + /// @brief Sets the object ID of the fill attributes used to display this rectangle's fill. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] fillAttributesObject The object ID of the fill attributes used to display this rectangle's fill + void set_fill_attributes(std::uint16_t fillAttributesObject); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 13; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t lineAttributes = NULL_OBJECT_ID; ///< Object ID of line attributes used to display this rectangle + std::uint16_t fillAttributes = NULL_OBJECT_ID; ///< Object ID of fill attributes used to display this rectangle + std::uint8_t lineSuppressionBitfield = 0; ///< Bitfield of line suppression options + }; + + /// @brief This object outputs an ellipse or circle shape + class OutputEllipse : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + LineAttributes = 1, + Width = 2, + Height = 3, + EllipseType = 4, + StartAngle = 5, + EndAngle = 6, + FillAttributes = 7, + + NumberOfAttributes = 8 + }; + + /// @brief Types of ellipse + enum class EllipseType + { + Closed = 0, ///< Closed ellipse + OpenDefinedByStartEndAngles = 1, ///< The ellipse is defined by start and end angles + ClosedEllipseSegment = 2, + ClosedEllipseSection = 3 + }; + + /// @brief Constructor for an output ellipse object + OutputEllipse() = default; + + /// @brief Virtual destructor for an output ellipse object + ~OutputEllipse() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the type of the ellipse + /// @returns The type of the ellipse + EllipseType get_ellipse_type() const; + + /// @brief Sets the ellipse type + /// @param[in] value The ellipse type to set + void set_ellipse_type(EllipseType value); + + /// @brief Returns the Start angle/2 (in degrees) from positive X axis + /// counter clockwise(90° is straight up) for the ellipse. + /// @details The range for this is 0 to 180. + /// @note If type > 0 and start and end angles are the same, the ellipse is drawn closed. + /// @returns Start angle/2 (in degrees) from positive X axis counter clockwise (90° is straight up) + std::uint8_t get_start_angle() const; + + /// @brief Sets the start angle for the ellipse + /// @note If type > 0 and start and end angles are the same, the ellipse is drawn closed. + /// @param[in] value Start angle/2 (in degrees) from positive X axis counter clockwise(90° is straight up) + void set_start_angle(std::uint8_t value); + + /// @brief Returns the end angle/2 (in degrees) from positive X axis counter clockwise(90° is straight up). + /// @details The range for this is 0 to 180. + /// @note If type > 0 and start and end angles are the same, the ellipse is drawn closed. + /// @returns End angle/2 (in degrees) from positive X axis counter clockwise (90° is straight up) + std::uint8_t get_end_angle() const; + + /// @brief Sets the end angle for the ellipse. + /// @note If type > 0 and start and end angles are the same, the ellipse is drawn closed. + /// @param[in] value The end angle/2 (in degrees) from positive X axis counter clockwise(90° is straight up). + void set_end_angle(std::uint8_t value); + + /// @brief Returns the object ID of the line attributes used to display this ellipse's lines + /// @returns The object ID of the line attributes used to display this ellipse's lines + std::uint16_t get_line_attributes() const; + + /// @brief Sets the object ID of the line attributes used to display this ellipse's lines. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] lineAttributesObject The object ID of the line attributes used to display this ellipse's lines + void set_line_attributes(std::uint16_t lineAttributesObject); + + /// @brief Returns the object ID of the fill attributes used to display this ellipse's fill + /// @returns The object ID of the fill attributes used to display this ellipse's fill + std::uint16_t get_fill_attributes() const; + + /// @brief Sets the object ID of the fill attributes used to display this ellipse's fill. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] fillAttributesObject The object ID of the fill attributes used to display this ellipse's fill + void set_fill_attributes(std::uint16_t fillAttributesObject); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 15; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t lineAttributes = NULL_OBJECT_ID; ///< Object ID of line attributes used to display this ellipse + std::uint16_t fillAttributes = NULL_OBJECT_ID; ///< Object ID of fill attributes used to display this ellipse + std::uint8_t ellipseType = 0; ///< The type of ellipse + std::uint8_t startAngle = 0; ///< Start angle/2 (in degrees) from positive X axis counter clockwise (90° is straight up). + std::uint8_t endAngle = 0; ///< End angle/2 (in degrees) from positive X axis counter clockwise (90° is straight up) + }; + + /// @brief This object outputs a polygon + class OutputPolygon : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + LineAttributes = 3, + FillAttributes = 4, + PolygonType = 5, + + NumberOfAttributes = 6 + }; + + /// @brief Polygon type. The first three types are useful only if the polygon is to be filled. + enum class PolygonType + { + Convex = 0, ///< On any given horizontal line, only two points on the polygon are encountered + NonConvex = 1, ///< On any given horizontal line, more than two points on the polygon edges can be encountered but the polygon edges do not cross + Complex = 2, ///< Similar to Non-convex but edges cross. Uses Complex Fill Algorithm + Open = 3 ///< This type cannot be filled + }; + + /// @brief Stores a cartesian polygon point + struct PolygonPoint + { + std::uint16_t xValue; ///< X value of a point relative to the top left corner of the polygon + std::uint16_t yValue; ///< Y value of a point relative to the top left corner of the polygon + }; + + /// @brief Constructor for an output polygon object + OutputPolygon() = default; + + /// @brief Virtual destructor for an output polygon object + ~OutputPolygon() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Adds a point to the polygon, defined by x and y coordinates + /// @param[in] x The X value of a point relative to the top left corner of the polygon + /// @param[in] y The Y value of a point relative to the top left corner of the polygon + void add_point(std::uint16_t x, std::uint16_t y); + + /// @brief Returns the number of polygon points + /// @returns The number of polygon points + std::uint8_t get_number_of_points() const; + + /// @brief Returns a point from the polygon by index + /// @param[in] index The index of the point to retrieve + /// @returns A point in the polygon by index, or zeros if the index is out of range. + PolygonPoint get_point(std::uint8_t index); + + /// @brief Returns the polygon type of this object + /// @returns The polygon type of this object + PolygonType get_type() const; + + /// @brief Sets the polygon type for this object + /// @param[in] value The new polygon type for this object + void set_type(PolygonType value); + + /// @brief Returns the object ID of the line attributes used to display this polygon's lines + /// @returns The object ID of the line attributes used to display this polygon's lines + std::uint16_t get_line_attributes() const; + + /// @brief Sets the object ID of the line attributes used to display this polygon's lines. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] lineAttributesObject The object ID of the line attributes used to display this polygon's lines + void set_line_attributes(std::uint16_t lineAttributesObject); + + /// @brief Returns the object ID of the fill attributes used to display this polygon's fill + /// @returns The object ID of the fill attributes used to display this polygon's fill + std::uint16_t get_fill_attributes() const; + + /// @brief Sets the object ID of the fill attributes used to display this polygon's fill. + /// Does not perform any error checking on the type of the object specified. + /// @param[in] fillAttributesObject The object ID of the fill attributes used to display this polygon's fill + void set_fill_attributes(std::uint16_t fillAttributesObject); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 14; ///< The fewest bytes of IOP data that can represent this object + + std::vector pointList; ///< List of points that make up the polygon. Must be at least 3 points! + std::uint16_t fillAttributes = NULL_OBJECT_ID; ///< Object ID of fill attributes used to display this polygon + std::uint16_t lineAttributes = NULL_OBJECT_ID; ///< Object ID of line attributes used to display this polygon + std::uint8_t polygonType = 0; ///< The polygon type. Affects how the object gets drawn. + }; + + /// @brief This object is a meter. Meter is drawn about a circle enclosed within a defined square. + class OutputMeter : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + NeedleColour = 2, + BorderColour = 3, + ArcAndTickColour = 4, + Options = 5, + NumberOfTicks = 6, + StartAngle = 7, + EndAngle = 8, + MinValue = 9, + MaxValue = 10, + VariableReference = 11, + Value = 12, + + NumberOfAttributes = 13 + }; + + /// @brief Options that can be applied to the input number + enum class Options : std::uint8_t + { + DrawArc = 0, ///< Draw Arc + DrawBorder = 1, ///< Draw Border + DrawTicks = 2, ///< Draw Ticks + DeflectionDirection = 3 ///< 0 = From min to max, counterclockwisee. 1 = from min to max, clockwise + }; + + /// @brief Constructor for an output meter object + OutputMeter() = default; + + /// @brief Virtual destructor for an output meter object + ~OutputMeter() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the minimum value of the output meter + /// @returns The minimum value of the output meter + std::uint16_t get_min_value() const; + + /// @brief Sets the minimum value of the output meter + /// @param[in] value The minimum value to set for the output meter + void set_min_value(std::uint16_t value); + + /// @brief Returns the max value for the output meter + /// @returns The max value for the output meter + std::uint16_t get_max_value() const; + + /// @brief Sets the max value for the output meter + /// @param[in] value The max value to set for the output meter + void set_max_value(std::uint16_t value); + + /// @brief Returns the value for the output meter (only matters if there's no child number variable object). + /// @returns The value of the output meter + std::uint16_t get_value() const; + + /// @brief Sets the value of the output meter (only matters if there's no child number variable object). + /// @param[in] value The value to set for the output meter + void set_value(std::uint16_t value); + + /// @brief Returns the value of the needle colour + /// @returns The value of the needle colour as an index into the VT colour table + std::uint8_t get_needle_colour() const; + + /// @brief Sets the value of the needle colour + /// @param[in] colourIndex The colour to set for the needle as an index into the VT colour table + void set_needle_colour(std::uint8_t colourIndex); + + /// @brief Returns the border colour of the meter + /// @returns The border colour of the meter as an index into the VT colour table + std::uint8_t get_border_colour() const; + + /// @brief Sets the border colour of the meter + /// @param[in] colourIndex The border colour to set for the meter as an index into the VT colour table + void set_border_colour(std::uint8_t colourIndex); + + /// @brief Returns the arc and tick colour for the meter + /// @returns The arc and tick colour for the meter as an index into the VT colour table + std::uint8_t get_arc_and_tick_colour() const; + + /// @brief Sets the arc and tick colour for the meter + /// @param[in] colourIndex The arc and tick colour to set for the meter as an index into the VT colour table + void set_arc_and_tick_colour(std::uint8_t colourIndex); + + /// @brief Returns the number of ticks to render across the meter + /// @returns The number of ticks to render across the meter + std::uint8_t get_number_of_ticks() const; + + /// @brief Sets the number of ticks to render when drawing the meter + /// @param[in] ticks The number of ticks to render + void set_number_of_ticks(std::uint8_t ticks); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] options The new value for the options bitfield + void set_options(std::uint8_t options); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] optionValue The new value of the option bit + void set_option(Options option, bool optionValue); + + /// @brief Returns the start angle for the meter + /// @note If the start and end angles are the same the meter’s arc is closed. + /// @returns Start angle/2 (in degrees) from positive X axis anticlockwise(90° is straight up). + std::uint8_t get_start_angle() const; + + /// @brief Sets the start angle for the meter + /// @note If the start and end angles are the same the meter’s arc is closed. + /// @param[in] value Start angle/2 (in degrees) from positive X axis anticlockwise(90° is straight up). + void set_start_angle(std::uint8_t value); + + /// @brief Returns the end angle of the meter. + /// @note If the start and end angles are the same the meter’s arc is closed. + /// @returns The end angle/2 (in degrees) from positive X axis anticlockwise(90° is straight up). + std::uint8_t get_end_angle() const; + + /// @brief Sets the end angle for this meter in degrees from the +x axis counter clockwise + /// @note If the start and end angles are the same the meter’s arc is closed. + /// @param[in] value End angle/2 (in degrees) from positive X axis anticlockwise(90° is straight up). + void set_end_angle(std::uint8_t value); + + /// @brief Returns the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// @returns The object ID of a number variable to use for the value, or NULL_OBJECT_ID if not used. + std::uint16_t get_variable_reference() const; + + /// @brief Sets the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// Does not do any checking on the type of the object ID. + /// @param[in] variableReferenceValue The object ID of a number variable to use for the target value + void set_variable_reference(std::uint16_t variableReferenceValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 21; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t minValue = 0; ///< Minimum value. Represents value when needle is at the start of arc + std::uint16_t maxValue = 0; ///< Maximum value. Represents when the needle is at the end of the arc. + std::uint16_t value = 0; ///< Current value. Needle position set to this value, used if variable ref is NULL. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Object ID of a number variable to use for the value, or NULL_OBJECT_ID if not used. + std::uint8_t needleColour = 0; ///< Needle (indicator) colour + std::uint8_t borderColour = 0; ///< Border colour (if drawn) + std::uint8_t arcAndTickColour = 0; ///< Meter arc and tick colour (if drawn) + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t numberOfTicks = 0; ///< Number of ticks to draw about meter arc + std::uint8_t startAngle = 0; ///< Start angle / 2 in degrees from positive X axis counterclockwise + std::uint8_t endAngle = 0; ///< End angle / 2 in degrees from positve X axis counterclockwise + }; + + /// @brief This is a linear bar graph or thermometer, defined by an enclosing rectangle. + class OutputLinearBarGraph : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + Colour = 3, + TargetLineColour = 4, + Options = 5, + NumberOfTicks = 6, + MinValue = 7, + MaxValue = 8, + VariableReference = 9, + TargetValueVariableReference = 10, + TargetValue = 11, + Value = 12, + + NumberOfAttributes = 13 + }; + + /// @brief Options that can be applied to the input number + enum class Options : std::uint8_t + { + DrawBorder = 0, ///< Draw Border + DrawTargetLine = 1, ///< Draw Target Line + DrawTicks = 2, ///< Draw Ticks + BarGraphType = 3, ///< 0 = Filled, 1 = not filled with value line + AxisOrientation = 4, ///< 0 = vertical, 1 = horizontal + Direction = 5 ///< 0 = Grows negative, 1 = Grows positive + }; + + /// @brief Constructor for an output linear bar graph object + OutputLinearBarGraph() = default; + + /// @brief Virtual destructor for an output linear bar graph object + ~OutputLinearBarGraph() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the minimum value on the graph. Used to scale the graph's range. + /// @returns The minimum value that will be shown on the graph. + std::uint16_t get_min_value() const; + + /// @brief Sets the minimum value on the graph. + /// @details Used to scale the graph's range. Values below this will be clamped to the min. + /// @param[in] value The minimum value to set + void set_min_value(std::uint16_t value); + + /// @brief Returns the max value for the graph + /// @returns The max value for the graph + std::uint16_t get_max_value() const; + + /// @brief Sets the max value for the graph + /// @param[in] value The max value to set for the graph + void set_max_value(std::uint16_t value); + + /// @brief Returns the value of the graph (only matters if there's no child number variable object). + /// @returns The value of the graph + std::uint16_t get_value() const; + + /// @brief Sets the value of the graph (only matters if there's no child number variable object). + /// @param[in] value The value to set for the graph + void set_value(std::uint16_t value); + + /// @brief Returns the graph's target value (only matters if there's no target value reference). + /// @returns The graph's target value + std::uint16_t get_target_value() const; + + /// @brief Sets the target value for the graph (only matters if there's no target value reference). + /// @param[in] valueTarget The target value to set + void set_target_value(std::uint16_t valueTarget); + + /// @brief Returns the target value reference object ID + /// @details This object will be used (if it's not NULL_OBJECT_ID) + /// to determine the target value of the graph instead of the target value itself. + /// @returns The object ID of a number variable to use for the target value + std::uint16_t get_target_value_reference() const; + + /// @brief Sets the target value reference object ID + /// @details This object will be used (if it's not NULL_OBJECT_ID) + /// to determine the target value of the graph instead of the target value itself. + /// @param[in] valueReferenceObjectID The object ID of a number variable to use for the target value + void set_target_value_reference(std::uint16_t valueReferenceObjectID); + + /// @brief Returns the number of ticks to render across the graph + /// @returns The number of ticks to render across the graph + std::uint8_t get_number_of_ticks() const; + + /// @brief Sets the number of ticks to render when drawing the graph + /// @param[in] value The number of ticks to graph + void set_number_of_ticks(std::uint8_t value); + + /// @brief Returns the colour of the graph + /// @returns The colour of the graph as an index into the VT colour table + std::uint8_t get_colour() const; + + /// @brief Sets the colour of the graph + /// @param[in] graphColour The colour of the graph to set as an index into the VT colour table + void set_colour(std::uint8_t graphColour); + + /// @brief Returns the target line colour as an index into the VT colour table + /// @returns The target line colour as an index into the VT colour table + std::uint8_t get_target_line_colour() const; + + /// @brief Sets the target line colour + /// @param[in] lineColour The colour to set for the target line as an index into the VT colour table + void set_target_line_colour(std::uint8_t lineColour); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] options The new value for the options bitfield + void set_options(std::uint8_t options); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] optionValue The new value of the option bit + void set_option(Options option, bool optionValue); + + /// @brief Returns the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// @returns The object ID of a number variable to use for the value, or NULL_OBJECT_ID if not used. + std::uint16_t get_variable_reference() const; + + /// @brief Sets the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// Does not do any checking on the type of the object ID. + /// @param[in] variableReferenceValue The object ID of a number variable to use for the target value + void set_variable_reference(std::uint16_t variableReferenceValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 24; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t minValue = 0; ///< Minimum value + std::uint16_t maxValue = 0; ///< Maximum value + std::uint16_t targetValue = 0; ///< Current target value. Used only if Target value variable Reference attribute is NULL. + std::uint16_t targetValueReference = NULL_OBJECT_ID; ///< Object ID of a Number Variable object in which to retrieve the bar graph’s target value. + std::uint16_t value = 0; ///< Current value. Needle position set to this value, used if variable ref is NULL. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Object ID of a Number Variable object in which to retrieve the bar graph’s value. + std::uint8_t numberOfTicks = 0; ///< Number of ticks to draw along the bar graph + std::uint8_t colour = 0; ///< Bar graph fill and border colour. + std::uint8_t targetLineColour = 0; ///< Target line colour (if drawn). + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + }; + + /// @brief TThis object is similar in concept to a linear bar graph but appears arched. Arched bar graphs are drawn about + /// an Output Ellipse object enclosed within a defined rectangle + class OutputArchedBarGraph : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Height = 2, + Colour = 3, + TargetLineColour = 4, + Options = 5, + StartAngle = 6, + EndAngle = 7, + BarGraphWidth = 8, + MinValue = 9, + MaxValue = 10, + VariableReference = 11, + TargetValueVariableReference = 12, + TargetValue = 13, + + NumberOfAttributes = 14 + }; + + /// @brief Options that can be applied to the input number + enum class Options : std::uint8_t + { + DrawBorder = 0, ///< Draw border + DrawTargetLine = 1, ///< Draw a target line + Undefined = 2, ///< Undefined, set to 0 recommended + BarGraphType = 3, ///< bar graph type. If this bit is FALSE (0), bar graph is filled + Deflection = 4 ///< 0 = anticlockwise and 1 = clockwise + }; + + /// @brief Constructor for an output arched bar graph object + OutputArchedBarGraph() = default; + + /// @brief Virtual destructor for an output arched bar graph object + ~OutputArchedBarGraph() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the width (px) of the bar graph + /// @returns The width (px) of the bar graph + std::uint16_t get_bar_graph_width() const; + + /// @brief Sets the width (px) of the bar graph + /// @param[in] width The width (px) to set for the bar graph + void set_bar_graph_width(std::uint16_t width); + + /// @brief Returns the minimum value of the bar graph. + /// @note Values below this will be clamped to the min when rendered. + /// @returns The minimum value of the bar graph + std::uint16_t get_min_value() const; + + /// @brief Sets the minimum value for the bar graph + /// @note Values below this will be clamped to the min when rendered. + /// @param[in] minimumValue The minimum value to set + void set_min_value(std::uint16_t minimumValue); + + /// @brief Returns the maximum value of the bar graph + /// @note Values above this will be clamped to the max when rendered. + /// @returns The maximum value of the bar graph + std::uint16_t get_max_value() const; + + /// @brief Sets the max value of the bar graph + /// @note Values above this will be clamped to the max when rendered. + /// @param[in] maximumValue The maximum value of the bar graph to set + void set_max_value(std::uint16_t maximumValue); + + /// @brief Returns the value of the bar graph (only matters when no child number variable is used) + /// @returns The value of the bar graph + std::uint16_t get_value() const; + + /// @brief Sets the value of the bar graph (only matters when no child number variable is used) + /// @param[in] value The value to set for the bar graph + void set_value(std::uint16_t value); + + /// @brief Returns the colour of the target line + /// @returns The colour of the target line as an index into the VT colour table + std::uint8_t get_target_line_colour() const; + + /// @brief Sets the colour of the target line + /// @param[in] value The colour to set as an index into the VT colour table + void set_target_line_colour(std::uint8_t value); + + /// @brief Returns the colour of the bar graph + /// @returns The colour of the bar graph as an index into the VT colour table + std::uint8_t get_colour() const; + + /// @brief Sets the colour of the bar graph + /// @param[in] value The colour to set for the bar graph as an index into the VT colour table + void set_colour(std::uint8_t value); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] options The new value for the options bitfield + void set_options(std::uint8_t options); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] optionValue The new value of the option bit + void set_option(Options option, bool optionValue); + + /// @brief Returns the start angle of the graph + /// @returns Start angle/2 (in degrees) from positive X axis anticlockwise (90° is straight up) for the graph + std::uint8_t get_start_angle() const; + + /// @brief Sets the start angle for the graph + /// @param[in] value Start angle/2 (in degrees) from positive X axis anticlockwise (90° is straight up) for the graph + void set_start_angle(std::uint8_t value); + + /// @brief Returns the end angle of the graph + /// @returns End angle/2 (in degrees) from positive X axis anticlockwise (90° is straight up) for the graph + std::uint8_t get_end_angle() const; + + /// @brief Sets the end angle for the graph + /// @param[in] value End angle/2 (in degrees) from positive X axis anticlockwise (90° is straight up) for the graph + void set_end_angle(std::uint8_t value); + + /// @brief Returns the target value of the graph (only matters when no target value reference is used) + /// @returns The target value of the graph + std::uint16_t get_target_value() const; + + /// @brief Sets the target value of the graph (only matters when no target value reference is used) + /// @param[in] value The target value of the graph + void set_target_value(std::uint16_t value); + + /// @brief Returns the target value reference object ID + /// @details This object will be used (if it's not NULL_OBJECT_ID) + /// to determine the target value of the graph instead of the target value itself. + /// @returns The object ID of a number variable to use for the target value + std::uint16_t get_target_value_reference() const; + + /// @brief Sets the target value reference object ID + /// @details This object will be used (if it's not NULL_OBJECT_ID) + /// to determine the target value of the graph instead of the target value itself. + /// @param[in] value The object ID of a number variable to use for the target value + void set_target_value_reference(std::uint16_t value); + + /// @brief Returns the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// @returns The object ID of a number variable to use for the value, or NULL_OBJECT_ID if not used. + std::uint16_t get_variable_reference() const; + + /// @brief Sets the value reference object ID, which is a number variable object + /// that should be used to determine the value of the graph instead of the value itself if it's not NULL_OBJECT_ID. + /// Does not do any checking on the type of the object ID. + /// @param[in] variableReferenceValue The object ID of a number variable to use for the target value + void set_variable_reference(std::uint16_t variableReferenceValue); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 27; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t barGraphWidth = 0; ///< Bar graph width in pixels. Bar graph width should be less than half the total width, or less than half the total height, whichever is least. + std::uint16_t minValue = 0; ///< Minimum value. Represents value when needle is at the start of arc + std::uint16_t maxValue = 0; ///< Maximum value. Represents when the needle is at the end of the arc. + std::uint16_t value = 0; ///< Current value. Needle position set to this value, used if variable ref is NULL. + std::uint16_t targetValue = 0; ///< Current target value. Used only if Target value variable Reference attribute is NULL. + std::uint16_t targetValueReference = NULL_OBJECT_ID; ///< Object ID of a Number Variable object in which to retrieve the bar graph’s target value. + std::uint16_t variableReference = NULL_OBJECT_ID; ///< Object ID of a Number Variable object in which to retrieve the bar graph’s value. + std::uint8_t targetLineColour = 0; ///< Target line colour (if drawn) + std::uint8_t colour = 0; ///< Bar graph fill and border colour + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t startAngle = 0; ///< Start angle / 2 in degrees from positive X axis counterclockwise + std::uint8_t endAngle = 0; ///< End angle / 2 in degrees from positive X axis counterclockwise + }; + + /// @brief This object displays a picture graphic (bitmap) + class PictureGraphic : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Width = 1, + Options = 2, + TransparencyColour = 3, + ActualWidth = 4, + ActualHeight = 5, + Format = 6, + + NumberOfAttributes = 7 + }; + + /// @brief Enumerates the different colour formats a picture graphic can have (mutually exclusive) + enum class Format + { + Monochrome = 0, ///< Monochrome; 8 pixels per byte. Each bit represents a colour palette index of 0 or 1. + FourBitColour = 1, ///< 2 colour pixels per byte. Each nibble(4 bits) represents a colour palette index of 0 through 15. + EightBitColour = 2 ///< colour pixel per byte. Each byte represents a colour palette index of 0 through 255 + }; + + /// @brief Enumerates the different options bits in the options bitfield + enum class Options + { + Transparent = 0, ///< 0 = Opaque, 1 = Transparent + Flashing = 1, ///< 0 = Normal, 1 = Flashing + RunLengthEncoded = 2 ///< Data is RLE See Clause B.12.2 Picture Graphic object raw data format and compression + }; + + /// @brief Constructor for a picture graphic (bitmap) object + PictureGraphic() = default; + + /// @brief Virtual destructor for a picture graphic (bitmap) object + ~PictureGraphic() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns a reference to the underlying bitmap data + /// @returns A reference to the underlying bitmap data + std::vector &get_raw_data(); + + /// @brief Sets a large chunk of data to the underlying bitmap + /// @param[in] data Pointer to a buffer of data + /// @param[in] size The length of the data buffer to add to the underlying bitmap + void set_raw_data(const std::uint8_t *data, std::uint32_t size); + + /// @brief Sets one byte of raw data to the underlying bitmap + /// @param[in] dataByte One byte of bitmap data + void add_raw_data(std::uint8_t dataByte); + + /// @brief Returns the number of bytes in the raw data that comprises the underlying bitmap + /// @returns The number of bytes in the raw data that comprises the underlying bitmap + std::uint32_t get_number_of_bytes_in_raw_data() const; + + /// @brief Sets the number of bytes in the raw data that comprises the underlying bitmap + /// @param[in] value The number of bytes in the raw data that comprises the underlying bitmap + void set_number_of_bytes_in_raw_data(std::uint32_t value); + + /// @brief Returns the actual width of the underlying bitmap + /// @returns The actual width of the underlying bitmap (px) + std::uint16_t get_actual_width() const; + + /// @brief Sets the actual width of the underlying bitmap + /// @param[in] value Actual width to set for the underlying bitmap (px) + void set_actual_width(std::uint16_t value); + + /// @brief Returns the actual height of the underlying bitmap + /// @returns The actual height of the underlying bitmap (px) + std::uint16_t get_actual_height() const; + + /// @brief Sets the actual height of the underlying bitmap + /// @param[in] value Actual height to set for the underlying bitmap (px) + void set_actual_height(std::uint16_t value); + + /// @brief Returns the picture's colour format + /// @returns The picture colour format + Format get_format() const; + + /// @brief Sets the picture's colour format + /// @param[in] value The colour format to use for this picture graphic + void set_format(Format value); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + /// @brief Returns the transparency colour to use when rendering the object as an index into the VT colour table + /// @returns Transparency colour to use when rendering the object as an index into the VT colour table + std::uint8_t get_transparency_colour() const; + + /// @brief Sets the transparency colour to use when rendering the object as an index into the VT colour table + /// @param[in] value The colour to use when rendering the object as an index into the VT colour table + void set_transparency_colour(std::uint8_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 17; ///< The fewest bytes of IOP data that can represent this object + + std::vector rawData; ///< The raw picture data. Not a standard bitmap, but rather indicies into the VT colour table. + std::uint32_t numberOfBytesInRawData = 0; ///< Number of bytes of raw data + std::uint16_t actualWidth = 0; ///< The actual width of the bitmap + std::uint16_t actualHeight = 0; ///< The actual height of the bitmap + std::uint8_t formatByte = 0; ///< The format option byte + std::uint8_t optionsBitfield = 0; ///< Options bitfield, see the `options` enum + std::uint8_t transparencyColour = 0; ///< The colour to render as transparent if so set in the options + }; + + /// @brief A number variable holds a 32-bit unsigned integer value + class NumberVariable : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Value = 1, + + NumberOfAttributes = 2 + }; + + /// @brief Constructor for a number variable object + NumberVariable() = default; + + /// @brief Virtual destructor for a number variable object + ~NumberVariable() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the number variable's value + /// @returns The number variable's value + std::uint32_t get_value() const; + + /// @brief Sets the number variable's value + /// @param[in] value The value to set for the number variable + void set_value(std::uint32_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 7; ///< The fewest bytes of IOP data that can represent this object + + std::uint32_t value = 0; ///< 32-bit unsigned integer value + }; + + /// @brief A String Variable holds a fixed length string. + class StringVariable : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + + NumberOfAttributes = 1 + }; + + /// @brief Constructor for a string variable object + StringVariable() = default; + + /// @brief Virtual destructor for a string variable object + ~StringVariable() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the actual string value stored in this object + /// @returns The string value stored in this object + std::string get_value() const; + + /// @brief Sets the actual string value stored in this object + /// @param[in] value The new string value for this object + void set_value(const std::string &value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + + std::string value; ///< The actual value of the string, for non utf-16 strings + }; + + /// @brief This object holds attributes related to fonts. + class FontAttributes : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + FontColour = 1, + FontSize = 2, + FontType = 3, + FontStyle = 4, + + NumberOfAttributes = 5 + }; + + /// @brief Enumerates the different font sizes + enum class FontSize : std::uint8_t + { + Size6x8 = 0, ///< 6x8 Font size + Size8x8 = 1, ///< 8x8 Font size + Size8x12 = 2, ///< 8x12 Font size + Size12x16 = 3, ///< 12x16 Font size + Size16x16 = 4, ///< 16x16 Font size + Size16x24 = 5, ///< 16x24 Font size + Size24x32 = 6, ///< 24x32 Font size + Size32x32 = 7, ///< 32x32 Font size + Size32x48 = 8, ///< 32x48 Font size + Size48x64 = 9, ///< 48x64 Font size + Size64x64 = 10, ///< 64x64 Font size + Size64x96 = 11, ///< 64x96 Font size + Size96x128 = 12, ///< 96x128 Font size + Size128x128 = 13, ///< 128x128 Font size + Size128x192 = 14 ///< 128x192 Font size + }; + + /// @brief Enumerates the font style options that can be encoded in a font style bitfield + enum class FontStyleBits : std::uint8_t + { + Bold = 0, ///< Bold font style + CrossedOut = 1, ///< Crossed-out font style (strikethrough) + Underlined = 2, ///< Underlined font style + Italic = 3, ///< Italic font style + Inverted = 4, ///< Inverted font style (upside down) + Flashing = 5, ///< Flashing font style + FlashingHidden = 6, ///< Flashing between hidden and shown font style + ProportionalFontRendering = 7 ///< Enables proportional font rendering if supported by the server + }; + + /// @brief Enumerates the different font types + enum class FontType : std::uint8_t + { + ISO8859_1 = 0, ///< ISO Latin 1 + ISO8859_15 = 1, ///< ISO Latin 9 + ISO8859_2 = 2, ///< ISO Latin 2 + Reserved_1 = 3, ///< Reserved + ISO8859_4 = 4, ///< ISO Latin 4 + ISO8859_5 = 5, ///< Cyrillic + Reserved_2 = 6, ///< Reserved + ISO8859_7 = 7, ///< Greek + ReservedEnd = 239, ///< Reserved from ISO8859_7 to this value + ProprietaryBegin = 240, ///< The beginning of the proprietary range + ProprietaryEnd = 255 ///< The end of the proprietary region + }; + + /// @brief Constructor for a font attributes object + FontAttributes() = default; + + /// @brief Virtual destructor for a font attributes object + ~FontAttributes() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the font type associated to this font attributes object + /// @returns The font type associated to this font attributes object + FontType get_type() const; + + /// @brief Sets the font type + /// @param[in] value The font type to set + void set_type(FontType value); + + /// @brief Returns the font style bitfield + /// @returns The style bitfield, which is comprised of FontStyleBits + std::uint8_t get_style() const; + + /// @brief Returns a specific font style bit's state + /// @param[in] styleSetting The font style bit to check + /// @returns The state of the selected style bit + bool get_style(FontStyleBits styleSetting) const; + + /// @brief Sets a specific font style bit to a new value + /// @param[in] bit The style bit to change + /// @param[in] value The state to set for the selected style bit + void set_style(FontStyleBits bit, bool value); + + /// @brief Sets the font style bitfield to a new value + /// @param[in] value The value to set to the font style bitfield + void set_style(std::uint8_t value); + + /// @brief Returns the font size + /// @returns The font size + FontSize get_size() const; + + /// @brief Sets the font size to a new value + /// @param[in] value The new font size + void set_size(FontSize value); + + /// @brief Returns the font colour as an index into the VT colour table + /// @returns The font colour as an index into the VT colour table + std::uint8_t get_colour() const; + + /// @brief Sets the colour of the font to a new VT colour + /// @param[in] value An index into the VT colour table associated to the desired colour + void set_colour(std::uint8_t value); + + /// @brief Returns the width of the associated font size in pixels + /// @returns The width of the associated font size in pixels + std::uint8_t get_font_width_pixels() const; + + /// @brief Returns the height of the associated font size in pixels + /// @returns The height of the associated font size in pixels + std::uint8_t get_font_height_pixels() const; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 8; ///< The fewest bytes of IOP data that can represent this object + + std::uint8_t colour = 0; ///< Text colour + std::uint8_t size = 0; ///< Font size + std::uint8_t type = 0; ///< Encoding type + std::uint8_t style = 0; ///< Font style + }; + + /// @brief Defines a line attributes object, which describes how lines should be displayed on the VT + class LineAttributes : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + LineColour = 1, + LineWidth = 2, + LineArt = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Constructor for a line attributes object + LineAttributes() = default; + + /// @brief Virtual destructor for a line attributes object + ~LineAttributes() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Sets the line art bit pattern. Each bit represents 1 pixel's on/off state. + /// @returns The line attribute's line art bit pattern + std::uint16_t get_line_art_bit_pattern() const; + + /// @brief Sets the line art bit patter for the line attribute + /// @param[in] value The line art bit pattern to set + void set_line_art_bit_pattern(std::uint16_t value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 8; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t lineArtBitpattern = 0; ///< Bit pattern art for line. Each bit represents a paintbrush spot + }; + + /// @brief This object holds attributes related to filling output shape objects + class FillAttributes : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + FillType = 1, + FillColour = 2, + FillPattern = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Enumerates the different fill types for an object + enum class FillType : std::uint8_t + { + NoFill = 0, ///< No fill will be applied + FillWithLineColor = 1, ///< Fill with the color of the outline of the shape + FillWithSpecifiedColorInFillColorAttribute = 2, ///< Fill with the color specified by a fill attribute + FillWithPatternGivenByFillPatternAttribute = 3 ///< Fill with a patter provided by a fill pattern attribute + }; + + /// @brief Constructor for a fill attributes object + FillAttributes() = default; + + /// @brief Virtual destructor for a fill attributes object + ~FillAttributes() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the fill pattern associated with this fill attributes object + /// @returns The fill pattern for this attribute object + std::uint16_t get_fill_pattern() const; + + /// @brief Sets the fill pattern for this fill attributes object + /// @param[in] value The fill pattern to set for this object + void set_fill_pattern(std::uint16_t value); + + /// @brief Returns the fill type/mode associated with this object + /// @returns The fill type/mode associated with this object + FillType get_type() const; + + /// @brief Sets the fill type/mode associated with this object + /// @param[in] value The fill type/mode associated with this object + void set_type(FillType value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 8; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t fillPattern = NULL_OBJECT_ID; ///< Object id of a Picture Graphic object to use as a Fill pattern + FillType type = FillType::NoFill; ///< The fill type/mode associated with this object + }; + + /// @brief This object defines the valid or invalid characters for an Input String object + class InputAttributes : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + ValidationType = 1, + + NumberOfAttributes = 2 + }; + + /// @brief Enumerates the different validation types for this object, which + /// describe how to interpret the validation string + enum class ValidationType : std::uint8_t + { + ValidCharactersAreListed = 0, + InvalidCharactersAreListed = 1 + }; + + /// @brief Constructor for a input attributes object + InputAttributes() = default; + + /// @brief Virtual destructor for a input attributes object + ~InputAttributes() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the validation string associated to this input attributes object + /// @returns The validation string associated to this input attributes object + std::string get_validation_string() const; + + /// @brief Sets the validation string for this object + /// @param[in] value The new validation string for this object + void set_validation_string(const std::string &value); + + /// @brief Returns the validation type setting for this object + /// @returns The validation type associated to this object + ValidationType get_validation_type() const; + + /// @brief Sets the validation type setting for this object + /// @param[in] newValidationType The validation type + void set_validation_type(ValidationType newValidationType); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 7; ///< The fewest bytes of IOP data that can represent this object + + std::string validationString; ///< String containing all valid or invalid character codes + ValidationType validationType = ValidationType::ValidCharactersAreListed; ///< Describes how to interpret the validation string + }; + + /// @brief The Extended Input Attributes object, available in VT version 4 and later, defines the valid or invalid + /// characters for an Input String object + class ExtendedInputAttributes : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + ValidationType = 1, + + NumberOfAttributes = 2 + }; + + /// @brief Enumerates the different validation types for this object, which + /// describe how to interpret the validation string + enum class ValidationType : std::uint8_t + { + ValidCharactersAreListed = 0, + InvalidCharactersAreListed = 1 + }; + + /// @brief Constructor for an extended input attributes object + ExtendedInputAttributes() = default; + + /// @brief Virtual destructor for an extended input attributes object + ~ExtendedInputAttributes() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the number of code planes in this extended input attributes + /// @returns The number of code planes in this extended input attributes + std::uint8_t get_number_of_code_planes() const; + + /// @brief Sets the number of code planes in this extended input attributes object + /// @param[in] value The new number of code planes + void set_number_of_code_planes(std::uint8_t value); + + /// @brief Returns the validation type setting for this object + /// @returns The validation type associated to this object + ValidationType get_validation_type() const; + + /// @brief Sets the validation type setting for this object + /// @param[in] value The validation type + void set_validation_type(ValidationType value); + + /// @todo Finish ExtendedInputAttributes implementation + + private: + /// @brief Stores data for a code plane (for utf-16 strings) + class CodePlane + { + public: + std::vector> characterRanges; ///< A list of character ranges for this code plane + std::uint8_t numberOfCharacterRanges; ///< The number of expected character ranges for this code plane + }; + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + + std::vector codePlanes; ///< Code planes to which the character ranges belong. + ValidationType validationType = ValidationType::ValidCharactersAreListed; ///< Describes how to interpret the validation string + }; + + /// @brief Points to another object + class ObjectPointer : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + Value = 1, + + NumberOfAttributes = 2 + }; + + /// @brief Constructor for a object pointer object + ObjectPointer() = default; + + /// @brief Virtual destructor for a object pointer object + ~ObjectPointer() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the object id of the object this object points to + /// @returns The object id of the object this object points to + std::uint16_t get_value() const; + + /// @brief Sets the object id of the object this object points to. + /// Does not do error checking on the type of object this object points to. + /// @param[in] objectIDToPointTo The object id of the object this object points to + void set_value(std::uint16_t objectIDToPointTo); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + std::uint16_t value = NULL_OBJECT_ID; ///< Object ID of the object this object points to, or the NULL Object ID if the pointer should not be drawn + }; + + /// @brief The External Object Pointer object, available in VT version 5 and later, allows a Working Set to display + /// objects that exist in another Working Set’s object pool + class ExternalObjectPointer : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + DefaultObjectID = 1, + ExternalReferenceNAMEID = 2, + ExternalObjectID = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Constructor for a object pointer object + ExternalObjectPointer() = default; + + /// @brief Virtual destructor for a object pointer object + ~ExternalObjectPointer() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the default object id which is the + /// object ID of an object which shall be displayed if the External Object ID is not valid, + /// or the NULL Object ID. + /// @returns The default object ID or the null object ID + std::uint16_t get_default_object_id() const; + + /// @brief Sets the default object id which is the + /// object ID of an object which shall be displayed if the External Object ID is not valid, + /// or the NULL Object ID. + /// @param[in] id The default object ID or the null object ID + void set_default_object_id(std::uint16_t id); + + /// @brief Returns the external reference NAME ID + /// @returns External reference NAME ID + std::uint16_t get_external_reference_name_id() const; + + /// @brief Sets the external reference NAME ID + /// @param[in] id External reference NAME ID + void set_external_reference_name_id(std::uint16_t id); + + /// @brief Returns the external object ID. + /// The referenced object is found in + /// the object pool of the Working Set Master + /// identified by the External Reference NAME + /// ID attribute and listed in the corresponding + /// External Object Definition object. + /// @returns The external object ID. + std::uint16_t get_external_object_id() const; + + /// @brief Sets the external object ID. + /// The referenced object is found in + /// the object pool of the Working Set Master + /// identified by the External Reference NAME + /// ID attribute and listed in the corresponding + /// External Object Definition object. + /// @param[in] id The external object ID. + void set_external_object_id(std::uint16_t id); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + + std::uint16_t defaultObjectID = NULL_OBJECT_ID; ///< Object ID of an object which shall be displayed if the External Object ID is not valid, or the NULL Object ID + std::uint16_t externalReferenceNAMEID = NULL_OBJECT_ID; ///< Object id of an External Reference NAME object or the NULL Object ID + std::uint16_t externalObjectID = NULL_OBJECT_ID; ///< Object ID of a referenced object or the NULL Object ID + }; + + /// @brief Defines a macro object. Performs a list of commands based on a message or event. + class Macro : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + + NumberOfAttributes = 1 + }; + + /// @brief A subset of the VT command multiplexors that support use in macros + enum class Command + { + HideShowObject = 0xA0, + EnableDisableObject = 0xA1, + SelectInputObject = 0xA2, + ControlAudioSignal = 0xA3, + SetAudioVolume = 0xA4, + ChangeChildLocation = 0xA5, + ChangeSize = 0xA6, + ChangeBackgroundColour = 0xA7, + ChangeNumericValue = 0xA8, + ChangeEndPoint = 0xA9, + ChangeFontAttributes = 0xAA, + ChangeLineAttributes = 0xAB, + ChangeFillAttributes = 0xAC, + ChangeActiveMask = 0xAD, + ChangeSoftKeyMask = 0xAE, + ChangeAttribute = 0xAF, + ChangePriority = 0xB0, + ChangeListItem = 0xB1, + ChangeStringValue = 0xB3, + ChangeChildPosition = 0xB4, + ChangeObjectLabel = 0xB5, + ChangePolygonPoint = 0xB6, + LockUnlockMask = 0xBD, + ExecuteMacro = 0xBE, + ChangePolygonScale = 0xB7, + GraphicsContextCommand = 0xB8, + SelectColourMap = 0xBA, + ExecuteExtendedMacro = 0xBC + }; + + /// @brief Constructor for a macro object + Macro() = default; + + /// @brief Virtual destructor for a macro object + ~Macro() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Adds a macro command packet to this macro. Essentially these are CAN messages that represent normal + /// ECU to VT commands that will be executed in order by this macro. + /// @param[in] command The command packet (CAN message data) to add + /// @returns true if the command was added to the macro, otherwise false (maybe the max number of commands has been hit) + bool add_command_packet(const std::vector &command); + + /// @brief Returns the number of stored command packets inside this macro (max 255) + /// @returns The number of stored command packets inside this macro + std::uint8_t get_number_of_commands() const; + + /// @brief Returns a command packet by index + /// @param[in] index The index of the packet to retrieve + /// @param[out] command The returned command packet if the return value is true, otherwise the returned + /// command packet content is undefined. + /// @returns true if a valid command packet was returned, otherwise false (index out of range) + bool get_command_packet(std::uint8_t index, std::vector &command); + + /// @brief Deletes a command packet from the macro by index + /// @param[in] index The index of the packet to delete + /// @returns true if the specified command packet was removed, otherwise false (index out of range) + bool remove_command_packet(std::uint8_t index); + + /// @brief Returns if the command packets in this macro are valid + /// @returns true if the command packets in this macro are valid, otherwise false + bool get_are_command_packets_valid() const; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + static const std::array ALLOWED_COMMANDS_LOOKUP_TABLE; ///< The list of all allowed commands in a table for easy lookup when validating macro content + std::vector> commandPackets; ///< Macro command list + }; + + /// @brief Defines a colour map object. The Colour Map object, optionally available in VT version 4 and 5, and mandatory in VT version 6 and + /// later, allows the Working Set designer to alter the transformation of the VT colour index values to the + /// defined RGB value. This provides a mechanism where the colours table can be changed at run-time. + class ColourMap : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + + NumberOfAttributes = 1 + }; + + /// @brief Constructor for a colour map object + ColourMap() = default; + + /// @brief Virtual destructor for a colour map object + ~ColourMap() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief This is used to initialize the colour map data to either 2, 16, or 256 colour indexes. + /// Values will be initialized from the default color table to the colour map data whenever this is called. + /// @param[in] value The number of colour indexes to initialize the colour map to + /// @returns true if the number of colour indexes was set, otherwise false (invalid value or value is unchanged) + bool set_number_of_colour_indexes(std::uint16_t value); + + /// @brief Returns the number of colour indexes in this colour map + /// @returns The number of colour indexes in this colour map (2, 16, or 256) + std::uint16_t get_number_of_colour_indexes() const; + + /// @brief Sets the colour map index to the specified value/colour + /// @param[in] index The index to set + /// @param[in] value The colour to set the index to + /// @returns true if the colour map index was set, otherwise false (index out of range) + bool set_colour_map_index(std::uint8_t index, std::uint8_t value); + + /// @brief Returns the colour index into the VT colour table at the specified index in this colour map + /// @param[in] index The index in this map to get the VT colour index for + /// @returns The VT colour index at the specified index in this colour map + std::uint8_t get_colour_map_index(std::uint8_t index) const; + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 5; ///< The fewest bytes of IOP data that can represent this object + std::vector colourMapData; ///< The actual colour map data, which remaps each index from the default table based on the size of this vector. + }; + + /// @brief Defines a window mask object + class WindowMask : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + Options = 2, + Name = 3, + + NumberOfAttributes = 4 + }; + + /// @brief Enumerates the different kinds of window masks which imply how they are displayed and what they contain + enum class WindowType : std::uint8_t + { + Freeform = 0, ///< the Working Set supplies and positions all child objects contained inside the window. In this case the Working Set has complete control over the look and feel of the window. + NumericOutputValueWithUnits1x1 = 1, ///< This window displays a single numeric output with units of measure in a single window cell. + NumericOutputValueNoUnits1x1 = 2, ///< This window displays a single numeric output with no units of measure in a single window cell. + StringOutputValue1x1 = 3, ///< This window displays a single string output in a single window cell. + NumericInputValueWithUnits1x1 = 4, ///< This window displays a single numeric input with units of measure in a single window cell + NumericInputValueNoUnits1x1 = 5, ///< This window displays a single numeric input with no units of measure in a single window cell + StringInputValue1x1 = 6, ///< This window displays a single string input in a single window cell + HorizontalLinearBarGraphNoUnits1x1 = 7, ///< This window displays a single horizontal linear bar graph in a single window cell + SingleButton1x1 = 8, ///< This window displays a single Button object in a single window cell + DoubleButton1x1 = 9, ///< This window displays two Button objects in a single window cell + NumericOutputValueWithUnits2x1 = 10, ///< This window displays a single numeric output with units of measure in two horizontal window cells + NumericOutputValueNoUnits2x1 = 11, ///< This window displays a single numeric output with no units of measure in two horizontal window cells + StringOutputValue2x1 = 12, ///< This window displays a single string output in two horizontal window cells. + NumericInputValueWithUnits2x1 = 13, ///< This window displays a single numeric input with units of measure in two horizontal window cells + NumericInputValueNoUnits2x1 = 14, ///< This window displays a single numeric input with no units of measure in two horizontal window cells + StringInputValue2x1 = 15, ///< This window displays a single string input in two horizontal window cells. + HorizontalLinearBarGraphNoUnits2x1 = 16, ///< This window displays a single horizontal linear bar graph in two horizontal window cells + SingleButton2x1 = 17, ///< This window displays a single Button object in two horizontal window cells + DoubleButton2x1 = 18 ///< This window displays two Button objects in two horizontal window cells + }; + + /// @brief Enumerates the bit indexes of options encoded in the object's options bitfield + enum class Options + { + Available = 0, ///< If 0 (FALSE) this window is not available for use at the present time, even though defined. + Transparent = 1 ///< Transparent. If this bit is 1, the background colour attribute shall not be used and the Window shall be transparent. + }; + + /// @brief Constructor for a window mask object + WindowMask() = default; + + /// @brief Virtual destructor for a window mask object + ~WindowMask() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns object ID of an Output String object or an Object Pointer object that points + /// to an Output String object that contains the string that gives a proper name to this object + /// @returns Object ID corresponding to this object's proper name + std::uint16_t get_name_object_id() const; + + /// @brief Sets the object ID of an Output String object or an Object Pointer object that points + /// to an Output String object that contains the string that gives a proper name to this object + /// @param[in] object The object ID that contains the string for this object's proper name + void set_name_object_id(std::uint16_t object); + + /// @brief Returns Object ID of an Output String object or an Object Pointer + /// object that points to an Output String object that + /// contains the string that supplies window title text + /// @returns Object ID corresponding to this object's window title text + std::uint16_t get_title_object_id() const; + + /// @brief Sets the Object ID of an Output String object or an Object Pointer + /// object that points to an Output String object that + /// contains the string that supplies window title text + /// @param[in] object The object ID that contains the string for this object's title text + void set_title_object_id(std::uint16_t object); + + /// @brief Returns the object ID of an output object that contains an icon for the window. + /// @returns The object ID of an output object that contains an icon for the window. + std::uint16_t get_icon_object_id() const; + + /// @brief Sets the object ID of an output object that contains an icon for the window. + /// @param[in] object The object ID of an output object that contains an icon for the window. + void set_icon_object_id(std::uint16_t object); + + /// @brief Returns the window type for this object + /// @returns The window type for this object + WindowType get_window_type() const; + + /// @brief Sets the window type for this object + /// @param[in] type The window type for this object + void set_window_type(WindowType type); + + /// @brief Returns the state of a single option in the object's option bitfield + /// @param[in] option The option to check the value of in the object's option bitfield + /// @returns The state of the associated option bit + bool get_option(Options option) const; + + /// @brief Sets the options bitfield for this object to a new value + /// @param[in] value The new value for the options bitfield + void set_options(std::uint8_t value); + + /// @brief Sets a single option in the options bitfield to the specified value + /// @param[in] option The option to set + /// @param[in] value The new value of the option bit + void set_option(Options option, bool value); + + private: + static constexpr std::uint32_t MIN_OBJECT_LENGTH = 17; ///< The fewest bytes of IOP data that can represent this object + std::uint16_t name = NULL_OBJECT_ID; ///< Object ID of an Output String object or an Object Pointer object that points to an Output String object that contains the string that gives a proper name to this object + std::uint16_t title = NULL_OBJECT_ID; ///< Object ID of an Output String object or an Object Pointer object that points to an Output String object that supplies window title text + std::uint16_t icon = NULL_OBJECT_ID; ///< Object ID of an Output object or an Object Pointer object that points to an Output object that contains an icon for the window + std::uint8_t optionsBitfield = 0; ///< Bitfield of options defined in `Options` enum + std::uint8_t windowType = 0; ///< The window type, which implies its size + }; + + /// @brief Defines an auxiliary function type 1 object + /// @details The Auxiliary Function Type 1 object defines the function attributes and designator of an Auxiliary Function. + /// @note This object is parsed and validated but not utilized by version 3 or later VTs in making Auxiliary Control Assignments + class AuxiliaryFunctionType1 : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + + NumberOfAttributes = 1 + }; + + /// @brief Enumerates the different kinds of auxiliary functions (type 1) + enum class FunctionType : std::uint8_t + { + LatchingBoolean = 0, + Analogue = 1, + NonLatchingBoolean = 2 + }; + + /// @brief Constructor for a auxiliary function type 1 object + AuxiliaryFunctionType1() = default; + + /// @brief Virtual destructor for a auxiliary function type 1 object + ~AuxiliaryFunctionType1() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the function type + /// @returns The function type + FunctionType get_function_type() const; + + /// @brief Sets the function type + /// @param[in] type The function type + void set_function_type(FunctionType type); + + private: + FunctionType functionType = FunctionType::LatchingBoolean; ///< The function type + }; + + /// @brief Defines an auxiliary function type 2 object + /// @details The Auxiliary Function Type 2 object defines the function attributes and designator of an Auxiliary Function. + class AuxiliaryFunctionType2 : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + FunctionAttributes = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Aux inputs must be one of these types, and the input and function types must match. + /// @details This is table J.5 in ISO 11783-6 (2018) + enum class FunctionType : std::uint8_t + { + BooleanLatchingOnOff = 0, ///< Two-position switch (maintains position) (Single Pole, Double Throw) + Analouge = 1, ///< Maintains position setting + BooleanNonLatchingIncreaseValue = 2, ///< Two-position switch (return to off) (Momentary Single Pole, Double Throw) + AnalougeReturnTo50Percent = 3, ///< Two way analogue (return to centre position) + AnalougeReturnTo0PercentIncreaseValue = 4, ///< One way analogue input (returns to 0%) + DualBooleanBothLatching = 5, ///< Three-Position Switch (latching in all positions) (Single Pole, Three Position, Centre Off) + DualBooleanBothNonLatching = 6, ///< Three-Position Switch, (returning to centre position) (Momentary Single Pole, Three Position, Centre Off) + DualBooleanLatchingUp = 7, ///< Three-Position Switch, latching in up position, momentary down (Single Pole, Three Position, Centre Off) + DualBooleanLatchingDown = 8, ///< Three-Position Switch, latching in down position, momentary up (Single Pole, Three Position, Centre Off) + CombinedAnalougeReturnTo50PercentWithDualBooleanLatching = 9, ///< Two way analogue (return to centre position) with latching Boolean at 0% and 100% positions + CombinedAnalougeMaintainsPositionWithDualBooleanLatching = 10, ///< Analogue maintains position setting with latching Boolean at 0% and 100% positions + QuadratureBooleanNonLatching = 11, ///< Two quadrature mounted Three-Position Switches, (returning to centre position) (Momentary Single Pole, Three Position, Centre Off) + QuadratureAnalouge = 12, ///< Two quadrature mounted analogue maintain position setting. The centre position of each analogue axis is at 50 % value + QuadratureAnalougeReturnTo50Percent = 13, ///< Two quadrature mounted analogue returns to centre position (The centre position of each analogue axis is at 50 %) + BidirectionalEncoder = 14, ///< Count increases when turning in the encoders "increase" direction and count decreases when turning in the opposite direction + ReservedRangeStart = 15, ///< Reserved for future use + ReservedRangeEnd = 31 ///< Used for Remove assignment command + }; + + /// @brief Enumerates bit offsets of attributes of auxiliary functions to be assigned to an input control + enum FunctionAttribute + { + CriticalControl = 5, ///< If this bit is 1, This function can only be controlled by a critical Auxiliary Input (see ISO 15077) + AssignmentRestriction = 6, ///< If this bit is 1, This function, if assigned, can only be assigned as specified in the Preferred Assignment command + SingleAssignment = 7, ///< If 1, Function shall not be assigned with other Auxiliary Functions to same input. Otherwise it can be assigned with other functions to the same input + }; + + /// @brief Constructor for a auxiliary function type 2 object + AuxiliaryFunctionType2() = default; + + /// @brief Virtual destructor for a auxiliary function type 2 object + ~AuxiliaryFunctionType2() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the function type + /// @returns The function type + FunctionType get_function_type() const; + + /// @brief Sets the function type + /// @param[in] type The function type + void set_function_type(FunctionType type); + + /// @brief returns the value of a specified function attribute + /// @param[in] attributeToCheck The function attribute to check + /// @returns The value of a specified function attribute + bool get_function_attribute(FunctionAttribute attributeToCheck) const; + + /// @brief Sets the value of a specified function attribute + /// @param[in] attributeToSet The function attribute to set + /// @param[in] value The value to set the function attribute to + void set_function_attribute(FunctionAttribute attributeToSet, bool value); + + private: + std::uint8_t functionAttributesBitfield = 0; ///< Bitfield of function attributes defined in `FunctionAttribute` enum plus the `FunctionType` + }; + + /// @brief Defines an auxiliary input type 1 object + /// @details The Auxiliary Input Type 1 object defines the designator, the key, switch or dial number and the function + /// type for an Auxiliary Input. + /// @note This object is parsed and validated but not utilized by version 3 or later VTs in making Auxiliary Control Assignments + class AuxiliaryInputType1 : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + + NumberOfAttributes = 1 + }; + + /// @brief Enumerates the different kinds of auxiliary functions (type 1) + enum class FunctionType : std::uint8_t + { + LatchingBoolean = 0, + Analogue = 1, + NonLatchingBoolean = 2 + }; + + /// @brief Constructor for a auxiliary input type 1 object + AuxiliaryInputType1() = default; + + /// @brief Virtual destructor for a auxiliary input type 1 object + ~AuxiliaryInputType1() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the function type + /// @returns The function type + FunctionType get_function_type() const; + + /// @brief Sets the function type + /// @param[in] type The function type + void set_function_type(FunctionType type); + + /// @brief Returns the identification number of the input. Maximum value is 250. + /// @details This number is used by the Auxiliary Input units to identify a + /// particular input when sending an Auxiliary Input status message. + /// @returns The identification number of the input + std::uint8_t get_input_id() const; + + /// @brief Sets the identification number of the input. Maximum value is 250. + /// @details This number is used by the Auxiliary Input units to identify a + /// particular input when sending an Auxiliary Input status message. + /// @param[in] id The identification number of the input + /// @returns true if the identification number was set, otherwise false (value was >250) + bool set_input_id(std::uint8_t id); + + private: + FunctionType functionType = FunctionType::LatchingBoolean; ///< The function type + std::uint8_t inputID = 0; ///< The identification number of the input. This number is used by the Auxiliary Input units to identify a particular input when sending an Auxiliary Input status message. + }; + + /// @brief Defines an auxiliary input type 2 object + class AuxiliaryInputType2 : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + BackgroundColour = 1, + FunctionAttributes = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Enumerates bit offsets of attributes of auxiliary inputs + enum FunctionAttribute + { + CriticalControl = 5, ///< If this bit is 1, This input can control a critical (auxiliary) function + AssignmentRestriction = 6, ///< Reserved, set to 0 + SingleAssignment = 7, ///< If 1, Input shall only be assigned to a single Auxiliary Function + }; + + /// @brief Constructor for a auxiliary input type 2 object + AuxiliaryInputType2() = default; + + /// @brief Virtual destructor for a auxiliary input type 2 object + ~AuxiliaryInputType2() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the type of input function that the input control performs when assigned + /// @returns The type of input function that the input control performs when assigned + AuxiliaryFunctionType2::FunctionType get_function_type() const; + + /// @brief Sets the type of input function that the input control performs when assigned + /// @param[in] type The type of input function that the input control performs when assigned + void set_function_type(AuxiliaryFunctionType2::FunctionType type); + + /// @brief returns the value of a specified function attribute + /// @param[in] attributeToCheck The function attribute to check + /// @returns The value of a specified function attribute + bool get_function_attribute(FunctionAttribute attributeToCheck) const; + + /// @brief Sets the value of a specified function attribute + /// @param[in] attributeToSet The function attribute to set + /// @param[in] value The value to set the function attribute to + void set_function_attribute(FunctionAttribute attributeToSet, bool value); + + private: + std::uint8_t functionAttributesBitfield = 0; ///< Bitfield of function attributes defined in `FunctionAttribute` enum plus the `FunctionType` + }; + + /// @brief Defines an auxiliary control designator type 2 object. + /// Auxiliary Control Designator Type 2 Object Pointers allow the Working Set to place Auxiliary Input + /// Type 2 and Auxiliary Function Type 2 designators in the Data Mask at Working Set defined coordinates. + class AuxiliaryControlDesignatorType2 : public VTObject + { + public: + /// @brief Enumerates this object's attributes which are assigned an attribute ID. + /// The Change Attribute command allows any writable attribute with an AID to be changed. + enum class AttributeName : std::uint8_t + { + Type = 0, + PointerType = 1, + AuxiliaryObjectID = 2, + + NumberOfAttributes = 3 + }; + + /// @brief Constructor for a auxiliary control designator type 2 object + AuxiliaryControlDesignatorType2() = default; + + /// @brief Virtual destructor for a auxiliary control designator type 2 object + ~AuxiliaryControlDesignatorType2() override = default; + + /// @brief Returns the VT object type of the underlying derived object + /// @returns The VT object type of the underlying derived object + VirtualTerminalObjectType get_object_type() const override; + + /// @brief Returns the minimum binary serialized length of the associated object + /// @returns The minimum binary serialized length of the associated object + std::uint32_t get_minumum_object_length() const override; + + /// @brief Performs basic error checking on the object and returns if the object is valid + /// @param[in] objectPool The object pool to use when validating the object + /// @returns `true` if the object passed basic error checks + bool get_is_valid(const std::map> &objectPool) const override; + + /// @brief Sets an attribute and optionally returns an error code in the last parameter + /// @param[in] attributeID The ID of the attribute to change + /// @param[in] rawAttributeData The raw data to change the attribute to, as decoded in little endian format with unused + /// bytes/bits set to zero. + /// @param[in] objectPool The object pool to use when validating the objects affected by setting this attribute + /// @param[out] returnedError If this function returns false, this will be the error code. If the function + /// returns true, this value is undefined. + /// @returns True if the attribute was changed, otherwise false (check the returnedError in this case to know why). + bool set_attribute(std::uint8_t attributeID, std::uint32_t rawAttributeData, const std::map> &objectPool, AttributeError &returnedError) override; + + /// @brief Gets an attribute and returns the raw data in the last parameter + /// @param[in] attributeID The ID of the attribute to get + /// @param[out] returnedAttributeData The raw data of the attribute, as decoded in little endian format with unused + /// bytes/bits set to zero. You may need to cast this to the correct type. If this function + /// returns false, this value is undefined. + /// @returns True if the attribute was retrieved, otherwise false (the attribute ID was invalid) + bool get_attribute(std::uint8_t attributeID, std::uint32_t &returnedAttributeData) const override; + + /// @brief Returns the object ID of the referenced auxiliary object or the null object ID. + /// Used in conjunction with the pointer type. + /// @returns The object ID of the referenced auxiliary object or the null object ID + std::uint16_t get_auxiliary_object_id() const; + + /// @brief Sets the object ID of the referenced auxiliary object + /// Used in conjunction with the pointer type. + /// @param[in] id The object ID of the referenced auxiliary object or the null object ID + void set_auxiliary_object_id(std::uint16_t id); + + /// @brief Returns the pointer type, which describes how this object should be rendered + /// @details If the pointer type is 0 or 2, the pointer points to Auxiliary Object referenced in the auxiliaryObjectID, or the working set object + /// and the VT shall display that auxiliary object designator (pointer type 0) or Working Set designator (pointer type 2). + /// If the Auxiliary Control designator Object Pointer is of pointer type 1 or 3, then this pointer references + /// Auxiliary Object(s) that have an assignment relationship to the object referenced by the auxiliary object + /// attribute within this object pool.The VT shall display the assigned auxiliary object designator (pointer type 1) or + /// its Working Set designator (pointer type 3). + /// If the pointer type is 1, the pointer points to + /// @returns The pointer type, which describes how this object should be rendered + std::uint8_t get_pointer_type() const; + + /// @brief Sets the pointer type which describes how this object should be rendered + /// @param[in] type The pointer type, which describes how this object should be rendered + void set_pointer_type(std::uint8_t type); + + private: + std::uint16_t auxiliaryObjectID = NULL_OBJECT_ID; ///< Object ID of a referenced Auxiliary Function or Auxiliary Input object or NULL_OBJECT_ID + std::uint8_t pointerType = 0; ///< The pointer type, defines how this should be rendered + }; + } // namespace isobus #endif // ISOBUS_VIRTUAL_TERMINAL_OBJECTS_HPP diff --git a/src/nmea2000_fast_packet_protocol.cpp b/src/nmea2000_fast_packet_protocol.cpp index 1e14292..9349bba 100644 --- a/src/nmea2000_fast_packet_protocol.cpp +++ b/src/nmea2000_fast_packet_protocol.cpp @@ -19,8 +19,8 @@ namespace isobus { - FastPacketProtocol::FastPacketProtocolSession::FastPacketProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex) : - sessionMessage(canPortIndex), + FastPacketProtocol::FastPacketProtocolSession::FastPacketProtocolSession(Direction sessionDirection) : + sessionMessage(CANMessage::create_invalid_message()), sessionCompleteCallback(nullptr), frameChunkCallback(nullptr), parent(nullptr), @@ -102,19 +102,16 @@ namespace isobus if (!get_session(tempSession, parameterGroupNumber, source, destination)) { - tempSession = new FastPacketProtocolSession(FastPacketProtocolSession::Direction::Transmit, source->get_can_port()); - tempSession->sessionMessage.set_source_control_function(source); - tempSession->sessionMessage.set_destination_control_function(destination); - tempSession->sessionMessage.set_identifier(CANIdentifier(CANIdentifier::Type::Extended, parameterGroupNumber, priority, (destination == nullptr ? 0xFF : destination->get_address()), source->get_address())); - if (data != nullptr) - { - tempSession->sessionMessage.set_data(data, messageLength); - } - else - { - tempSession->frameChunkCallback = frameChunkCallback; - tempSession->frameChunkCallbackMessageLength = messageLength; - } + tempSession = new FastPacketProtocolSession(FastPacketProtocolSession::Direction::Transmit); + CANIdentifier identifier(CANIdentifier::Type::Extended, parameterGroupNumber, priority, (destination == nullptr ? 0xFF : destination->get_address()), source->get_address()); + tempSession->sessionMessage = CANMessage(CANMessage::Type::Transmit, + identifier, + data, + messageLength, + source, + destination, + source->get_can_port()); + tempSession->parent = parentPointer; tempSession->packetCount = ((messageLength - 6) / PROTOCOL_BYTES_PER_FRAME); tempSession->timestamp_ms = SystemTiming::get_timestamp_ms(); @@ -137,12 +134,12 @@ namespace isobus else { // Already in a matching session, can't start another. - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[FP]: Can't send fast packet message, already in matching session."); + CANStackLogger::warn("[FP]: Can't send fast packet message, already in matching session."); } } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[FP]: Can't send fast packet message, bad parameters or ICF is invalid"); + CANStackLogger::error("[FP]: Can't send fast packet message, bad parameters or ICF is invalid"); } return retVal; } @@ -189,11 +186,11 @@ namespace isobus } } - void FastPacketProtocol::close_session(FastPacketProtocolSession *session, bool successfull) + void FastPacketProtocol::close_session(FastPacketProtocolSession *session, bool successful) { if (nullptr != session) { - process_session_complete_callback(session, successfull); + process_session_complete_callback(session, successful); for (auto currentSession = activeSessions.begin(); currentSession != activeSessions.end(); currentSession++) { if (session == *currentSession) @@ -317,7 +314,7 @@ namespace isobus } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[FP]: Existing session matched new frame counter, aborting the matching session."); + CANStackLogger::error("[FP]: Existing session matched new frame counter, aborting the matching session."); close_session(currentSession, false); } } @@ -329,7 +326,7 @@ namespace isobus if (messageData[1] <= MAX_PROTOCOL_MESSAGE_LENGTH) { // This is the beginning of a new message - currentSession = new FastPacketProtocolSession(FastPacketProtocolSession::Direction::Receive, message.get_can_port_index()); + currentSession = new FastPacketProtocolSession(FastPacketProtocolSession::Direction::Receive); currentSession->frameChunkCallback = nullptr; if (messageData[1] >= PROTOCOL_BYTES_PER_FRAME - 1) { @@ -341,10 +338,15 @@ namespace isobus } currentSession->lastPacketNumber = ((messageData[0] >> SEQUENCE_NUMBER_BIT_OFFSET) & SEQUENCE_NUMBER_BIT_MASK); currentSession->processedPacketsThisSession = 1; + + currentSession->sessionMessage = CANMessage(CANMessage::Type::Receive, + message.get_identifier(), + nullptr, + 0, + message.get_source_control_function(), + message.get_destination_control_function(), + message.get_can_port_index()); currentSession->sessionMessage.set_data_size(messageData[1]); - currentSession->sessionMessage.set_identifier(message.get_identifier()); - currentSession->sessionMessage.set_source_control_function(message.get_source_control_function()); - currentSession->sessionMessage.set_destination_control_function(message.get_destination_control_function()); currentSession->timestamp_ms = SystemTiming::get_timestamp_ms(); if (0 != (messageData[1] % PROTOCOL_BYTES_PER_FRAME)) @@ -365,14 +367,14 @@ namespace isobus } else { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[FP]: Ignoring possible new FP session with advertised length > 233."); + CANStackLogger::warn("[FP]: Ignoring possible new FP session with advertised length > 233."); } } else { // This is the middle of some message that we have no context for. // Ignore the message for now until we receive it with a fresh packet counter. - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Warning, "[FP]: Ignoring FP message with PGN %u, no context available. The message may be processed when packet count returns to zero.", message.get_identifier().get_parameter_group_number()); + CANStackLogger::warn("[FP]: Ignoring FP message with PGN %u, no context available. The message may be processed when packet count returns to zero.", message.get_identifier().get_parameter_group_number()); } } } @@ -418,7 +420,7 @@ namespace isobus { if (SystemTiming::time_expired_ms(session->timestamp_ms, FP_TIMEOUT_MS)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[FP]: Rx session timed out."); + CANStackLogger::error("[FP]: Rx session timed out."); close_session(session, false); } } @@ -517,7 +519,7 @@ namespace isobus { if (SystemTiming::time_expired_ms(session->timestamp_ms, FP_TIMEOUT_MS)) { - CANStackLogger::CAN_stack_log(CANStackLogger::LoggingLevel::Error, "[FP]: Tx session timed out."); + CANStackLogger::error("[FP]: Tx session timed out."); close_session(session, false); txSessionCancelled = true; } diff --git a/src/nmea2000_fast_packet_protocol.hpp b/src/nmea2000_fast_packet_protocol.hpp index 84a2d33..39f20f0 100644 --- a/src/nmea2000_fast_packet_protocol.hpp +++ b/src/nmea2000_fast_packet_protocol.hpp @@ -95,10 +95,12 @@ namespace isobus enum class Direction { Transmit, ///< We are transmitting a message - Receive ///< We are receving a message + Receive ///< We are receiving a message }; - /// @brief A useful way to compare sesson objects to each other for equality + /// @brief A useful way to compare session objects to each other for equality + /// @param[in] obj The object to compare against + /// @returns true if the objects are equal, false otherwise bool operator==(const FastPacketProtocolSession &obj); /// @brief Get the total number of bytes that will be sent or received in this session @@ -110,8 +112,7 @@ namespace isobus /// @brief The constructor for a TP session /// @param[in] sessionDirection Tx or Rx - /// @param[in] canPortIndex The CAN channel index for the session - FastPacketProtocolSession(Direction sessionDirection, std::uint8_t canPortIndex); + explicit FastPacketProtocolSession(Direction sessionDirection); /// @brief The destructor for a TP session ~FastPacketProtocolSession(); @@ -144,7 +145,7 @@ namespace isobus /// @brief Ends a session and cleans up the memory associated with its metadata /// @param[in] session The session to close /// @param[in] successful `true` if the session was closed successfully, otherwise `false` - void close_session(FastPacketProtocolSession *session, bool successfull); + void close_session(FastPacketProtocolSession *session, bool successful); /// @brief Gets the sequence number to use for a new session based on the history /// @param[in] session The new session we're starting @@ -155,7 +156,7 @@ namespace isobus /// @param[in,out] returnedSession The returned session /// @param[in] parameterGroupNumber The PGN /// @param[in] source The session source control function - /// @param[in] destination The sesssion destination control function + /// @param[in] destination The session destination control function /// @returns `true` if a session was found that matches, otherwise `false` bool get_session(FastPacketProtocolSession *&returnedSession, std::uint32_t parameterGroupNumber, std::shared_ptr source, std::shared_ptr destination); diff --git a/src/nmea2000_message_definitions.cpp b/src/nmea2000_message_definitions.cpp new file mode 100644 index 0000000..7e8f002 --- /dev/null +++ b/src/nmea2000_message_definitions.cpp @@ -0,0 +1,1154 @@ +//================================================================================================ +/// @file nmea2000_message_definitions.cpp +/// +/// @brief This file contains class implementation will comprise the individual components +/// of the NMEA2000 message interface for the stack. Generally this separation exists to keep +/// the file size of nmea2000_message_interface.hpp/cpp smaller. +/// +/// @note This library and its authors are not affiliated with the National Marine +/// Electronics Association in any way. +/// +/// @author Adrian Del Grosso +/// +/// @copyright 2023 Adrian Del Grosso +//================================================================================================ +#include "nmea2000_message_definitions.hpp" +#include "can_message.hpp" +#include "can_stack_logger.hpp" +#include "system_timing.hpp" + +namespace isobus +{ + namespace NMEA2000Messages + { + VesselHeading::VesselHeading(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr VesselHeading::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t VesselHeading::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool VesselHeading::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (timestamp != messageTimestamp_ms); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::uint16_t VesselHeading::get_raw_heading() const + { + return headingReading; + } + + float VesselHeading::get_heading() const + { + return (headingReading * 1E-4f); + } + + bool VesselHeading::set_heading(std::uint16_t heading) + { + bool retVal = (heading != headingReading); + headingReading = heading; + return retVal; + } + + std::int16_t VesselHeading::get_raw_magnetic_deviation() const + { + return magneticDeviation; + } + + float VesselHeading::get_magnetic_deviation() const + { + return (magneticDeviation * 1E-4f); + } + + bool VesselHeading::set_magnetic_deviation(std::int16_t deviation) + { + bool retVal = (deviation != magneticDeviation); + magneticDeviation = deviation; + return retVal; + } + + std::int16_t VesselHeading::get_raw_magnetic_variation() const + { + return magneticVariation; + } + + float VesselHeading::get_magnetic_variation() const + { + return (magneticVariation * 1E-4f); + } + + bool VesselHeading::set_magnetic_variation(std::int16_t variation) + { + bool retVal = (variation != magneticVariation); + magneticVariation = variation; + return retVal; + } + + std::uint8_t VesselHeading::get_sequence_id() const + { + return sequenceID; + } + + bool VesselHeading::set_sequence_id(std::uint8_t sequenceNumber) + { + bool retVal = (sequenceNumber != sequenceID); + sequenceID = sequenceNumber; + return retVal; + } + + VesselHeading::HeadingSensorReference VesselHeading::get_sensor_reference() const + { + return sensorReference; + } + + bool VesselHeading::set_sensor_reference(HeadingSensorReference reference) + { + bool retVal = (sensorReference != reference); + sensorReference = reference; + return retVal; + } + + void VesselHeading::serialize(std::vector &buffer) const + { + buffer.resize(CAN_DATA_LENGTH); + buffer.at(0) = (sequenceID <= MAX_SEQUENCE_ID) ? sequenceID : 0xFF; + buffer.at(1) = static_cast(headingReading & 0xFF); + buffer.at(2) = static_cast((headingReading >> 8) & 0xFF); + buffer.at(3) = static_cast(magneticDeviation & 0xFF); + buffer.at(4) = static_cast((magneticDeviation >> 8) & 0xFF); + buffer.at(5) = static_cast(magneticVariation & 0xFF); + buffer.at(6) = static_cast((magneticVariation >> 8) & 0xFF); + buffer.at(7) = static_cast(sensorReference) & 0x03; + buffer.at(7) |= 0xFC; + } + + bool VesselHeading::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (CAN_DATA_LENGTH == receivedMessage.get_data_length()) + { + retVal |= set_sequence_id(receivedMessage.get_uint8_at(0)); + retVal |= set_heading(receivedMessage.get_uint16_at(1)); + retVal |= set_magnetic_deviation(receivedMessage.get_uint16_at(3)); + retVal |= set_magnetic_variation(receivedMessage.get_uint16_at(5)); + retVal |= set_sensor_reference(static_cast(receivedMessage.get_uint8_at(7) & 0x03)); + set_timestamp(SystemTiming::get_timestamp_ms()); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't deserialize vessel heading. DLC must be 8."); + } + return retVal; + } + + std::uint32_t VesselHeading::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + RateOfTurn::RateOfTurn(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr RateOfTurn::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t RateOfTurn::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool RateOfTurn::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::int32_t RateOfTurn::get_raw_rate_of_turn() const + { + return rateOfTurn; + } + + double RateOfTurn::get_rate_of_turn() const + { + return (static_cast(rateOfTurn) * (1.0 / 32.0 * 1E-6)); + } + + bool RateOfTurn::set_rate_of_turn(std::int32_t turnRate) + { + bool retVal = (rateOfTurn != turnRate); + rateOfTurn = turnRate; + return retVal; + } + + std::uint8_t RateOfTurn::get_sequence_id() const + { + return sequenceID; + } + + bool RateOfTurn::set_sequence_id(std::uint8_t sequenceNumber) + { + bool retVal = (sequenceID != sequenceNumber); + sequenceID = sequenceNumber; + return retVal; + } + + void RateOfTurn::serialize(std::vector &buffer) const + { + buffer.resize(CAN_DATA_LENGTH); + + buffer.at(0) = (sequenceID <= MAX_SEQUENCE_ID) ? sequenceID : 0xFF; + buffer.at(1) = static_cast(rateOfTurn & 0xFF); + buffer.at(2) = static_cast((rateOfTurn >> 8) & 0xFF); + buffer.at(3) = static_cast((rateOfTurn >> 16) & 0xFF); + buffer.at(4) = static_cast((rateOfTurn >> 24) & 0xFF); + buffer.at(5) = 0xFF; // Reserved bytes + buffer.at(6) = 0xFF; + buffer.at(7) = 0xFF; + } + + bool RateOfTurn::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (CAN_DATA_LENGTH == receivedMessage.get_data_length()) + { + auto turnRate = static_cast(receivedMessage.get_uint8_at(1)); + turnRate |= (static_cast(receivedMessage.get_uint8_at(2)) << 8); + turnRate |= (static_cast(receivedMessage.get_uint8_at(3)) << 16); + turnRate |= (static_cast(receivedMessage.get_uint8_at(4)) << 24); + retVal |= set_sequence_id(receivedMessage.get_uint8_at(0)); + retVal |= set_rate_of_turn(turnRate); + set_timestamp(SystemTiming::get_timestamp_ms()); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't deserialize rate of turn. DLC must be 8."); + } + return retVal; + } + + std::uint32_t RateOfTurn::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + PositionRapidUpdate::PositionRapidUpdate(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr PositionRapidUpdate::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t PositionRapidUpdate::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool PositionRapidUpdate::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::int32_t PositionRapidUpdate::get_raw_latitude() const + { + return latitude; + } + + double PositionRapidUpdate::get_latitude() const + { + return (static_cast(latitude) * 1E-7); + } + + double PositionRapidUpdate::get_longitude() const + { + return (static_cast(longitude) * 1E-7); + } + + std::int32_t PositionRapidUpdate::get_raw_longitude() const + { + return longitude; + } + + bool PositionRapidUpdate::set_latitude(std::int32_t latitudeToSet) + { + bool retVal = (latitude != latitudeToSet); + latitude = latitudeToSet; + return retVal; + } + + bool PositionRapidUpdate::set_longitude(std::int32_t longitudeToSet) + { + bool retVal = (longitude != longitudeToSet); + longitude = longitudeToSet; + return retVal; + } + + void PositionRapidUpdate::serialize(std::vector &buffer) const + { + buffer.resize(CAN_DATA_LENGTH); + + buffer.at(0) = static_cast(latitude & 0xFF); + buffer.at(1) = static_cast((latitude >> 8) & 0xFF); + buffer.at(2) = static_cast((latitude >> 16) & 0xFF); + buffer.at(3) = static_cast((latitude >> 24) & 0xFF); + buffer.at(4) = static_cast(longitude & 0xFF); + buffer.at(5) = static_cast((longitude >> 8) & 0xFF); + buffer.at(6) = static_cast((longitude >> 16) & 0xFF); + buffer.at(7) = static_cast((longitude >> 24) & 0xFF); + } + + bool PositionRapidUpdate::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (CAN_DATA_LENGTH == receivedMessage.get_data_length()) + { + auto decodedLatitude = static_cast(receivedMessage.get_uint8_at(0)); + decodedLatitude |= (static_cast(receivedMessage.get_uint8_at(1)) << 8); + decodedLatitude |= (static_cast(receivedMessage.get_uint8_at(2)) << 16); + decodedLatitude |= (static_cast(receivedMessage.get_uint8_at(3)) << 24); + auto decodedLongitude = static_cast(receivedMessage.get_uint8_at(4)); + decodedLongitude |= (static_cast(receivedMessage.get_uint8_at(5)) << 8); + decodedLongitude |= (static_cast(receivedMessage.get_uint8_at(6)) << 16); + decodedLongitude |= (static_cast(receivedMessage.get_uint8_at(7)) << 24); + retVal |= set_latitude(decodedLatitude); + retVal |= set_longitude(decodedLongitude); + set_timestamp(SystemTiming::get_timestamp_ms()); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't deserialize position rapid update. DLC must be 8."); + } + return retVal; + } + + std::uint32_t PositionRapidUpdate::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + CourseOverGroundSpeedOverGroundRapidUpdate::CourseOverGroundSpeedOverGroundRapidUpdate(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr CourseOverGroundSpeedOverGroundRapidUpdate::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t CourseOverGroundSpeedOverGroundRapidUpdate::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::uint16_t CourseOverGroundSpeedOverGroundRapidUpdate::get_raw_course_over_ground() const + { + return courseOverGround; + } + + float CourseOverGroundSpeedOverGroundRapidUpdate::get_course_over_ground() const + { + return (1E-4f * courseOverGround); + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::set_course_over_ground(std::uint16_t course) + { + bool retVal = (courseOverGround != course); + courseOverGround = course; + return retVal; + } + + std::uint16_t CourseOverGroundSpeedOverGroundRapidUpdate::get_raw_speed_over_ground() const + { + return speedOverGround; + } + + float CourseOverGroundSpeedOverGroundRapidUpdate::get_speed_over_ground() const + { + return (1E-2f * speedOverGround); + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::set_speed_over_ground(std::uint16_t speed) + { + bool retVal = (speedOverGround != speed); + speedOverGround = speed; + return retVal; + } + + std::uint8_t CourseOverGroundSpeedOverGroundRapidUpdate::get_sequence_id() const + { + return sequenceID; + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::set_sequence_id(std::uint8_t sequenceNumber) + { + bool retVal = (sequenceID != sequenceNumber); + sequenceID = sequenceNumber; + return retVal; + } + + CourseOverGroundSpeedOverGroundRapidUpdate::CourseOverGroundReference CourseOverGroundSpeedOverGroundRapidUpdate::get_course_over_ground_reference() const + { + return cogReference; + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::set_course_over_ground_reference(CourseOverGroundReference reference) + { + bool retVal = (cogReference != reference); + cogReference = reference; + return retVal; + } + + void CourseOverGroundSpeedOverGroundRapidUpdate::serialize(std::vector &buffer) const + { + buffer.resize(CAN_DATA_LENGTH); + + buffer.at(0) = sequenceID; + buffer.at(1) = (0xFC | static_cast(cogReference)); + buffer.at(2) = static_cast(courseOverGround & 0xFF); + buffer.at(3) = static_cast((courseOverGround >> 8) & 0xFF); + buffer.at(4) = static_cast(speedOverGround & 0xFF); + buffer.at(5) = static_cast((speedOverGround >> 8) & 0xFF); + buffer.at(6) = 0xFF; // Reserved + buffer.at(7) = 0xFF; // Reserved + } + + bool CourseOverGroundSpeedOverGroundRapidUpdate::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (CAN_DATA_LENGTH == receivedMessage.get_data_length()) + { + retVal |= set_sequence_id(receivedMessage.get_uint8_at(0)); + retVal |= set_course_over_ground_reference(static_cast(receivedMessage.get_uint8_at(1) & 0x03)); + retVal |= set_course_over_ground(receivedMessage.get_uint16_at(2)); + retVal |= set_speed_over_ground(receivedMessage.get_uint16_at(4)); + set_timestamp(SystemTiming::get_timestamp_ms()); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't deserialize COG/SOG rapid update. DLC must be 8."); + } + return retVal; + } + + std::uint32_t CourseOverGroundSpeedOverGroundRapidUpdate::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + PositionDeltaHighPrecisionRapidUpdate::PositionDeltaHighPrecisionRapidUpdate(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr PositionDeltaHighPrecisionRapidUpdate::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t PositionDeltaHighPrecisionRapidUpdate::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool PositionDeltaHighPrecisionRapidUpdate::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::int32_t PositionDeltaHighPrecisionRapidUpdate::get_raw_latitude_delta() const + { + return latitudeDelta; + } + + double PositionDeltaHighPrecisionRapidUpdate::get_latitude_delta() const + { + return (static_cast(latitudeDelta) * 10E-7); + } + + bool PositionDeltaHighPrecisionRapidUpdate::set_latitude_delta(std::int32_t delta) + { + bool retVal = (latitudeDelta != delta); + latitudeDelta = delta; + return retVal; + } + + std::int32_t PositionDeltaHighPrecisionRapidUpdate::get_raw_longitude_delta() const + { + return longitudeDelta; + } + + double PositionDeltaHighPrecisionRapidUpdate::get_longitude_delta() const + { + return (static_cast(longitudeDelta) * 10E-7); + } + + bool PositionDeltaHighPrecisionRapidUpdate::set_longitude_delta(std::int32_t delta) + { + bool retVal = (longitudeDelta != delta); + longitudeDelta = delta; + return retVal; + } + + std::uint8_t PositionDeltaHighPrecisionRapidUpdate::get_sequence_id() const + { + return sequenceID; + } + + bool PositionDeltaHighPrecisionRapidUpdate::set_sequence_id(std::uint8_t sequenceNumber) + { + bool retVal = (sequenceNumber != sequenceID); + sequenceID = sequenceNumber; + return retVal; + } + + std::uint8_t PositionDeltaHighPrecisionRapidUpdate::get_raw_time_delta() const + { + return timeDelta; + } + + double PositionDeltaHighPrecisionRapidUpdate::get_time_delta() const + { + return ((static_cast(timeDelta) * 5.0) / 1000.0); + } + + bool PositionDeltaHighPrecisionRapidUpdate::set_time_delta(std::uint8_t delta) + { + bool retVal = (timeDelta != delta); + timeDelta = delta; + return retVal; + } + + void PositionDeltaHighPrecisionRapidUpdate::serialize(std::vector &buffer) const + { + buffer.resize(CAN_DATA_LENGTH); + + buffer.at(0) = sequenceID; + buffer.at(1) = timeDelta; + buffer.at(2) = static_cast(latitudeDelta & 0xFF); + buffer.at(3) = static_cast((latitudeDelta >> 8) & 0xFF); + buffer.at(4) = static_cast((latitudeDelta >> 16) & 0xFF); + buffer.at(5) = static_cast(longitudeDelta & 0xFF); + buffer.at(6) = static_cast((longitudeDelta >> 8) & 0xFF); + buffer.at(7) = static_cast((longitudeDelta >> 16) & 0xFF); + } + + bool PositionDeltaHighPrecisionRapidUpdate::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (CAN_DATA_LENGTH == receivedMessage.get_data_length()) + { + retVal = set_sequence_id(receivedMessage.get_uint8_at(0)); + retVal |= set_time_delta(receivedMessage.get_uint8_at(1)); + retVal |= set_latitude_delta(receivedMessage.get_uint24_at(2)); + retVal |= set_longitude_delta(receivedMessage.get_uint24_at(5)); + set_timestamp(SystemTiming::get_timestamp_ms()); + } + else + { + CANStackLogger::warn("[NMEA2K]: Cannot deserialize position delta high precision rapid update. DLC must be 8 bytes."); + } + return retVal; + } + + std::uint32_t PositionDeltaHighPrecisionRapidUpdate::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + GNSSPositionData::GNSSPositionData(std::shared_ptr source) : + senderControlFunction(source) + { + } + + std::shared_ptr GNSSPositionData::get_control_function() const + { + return senderControlFunction; + } + + std::int64_t GNSSPositionData::get_raw_altitude() const + { + return altitude; + } + + double GNSSPositionData::get_altitude() const + { + return (static_cast(altitude) * 1E-6); + } + + bool GNSSPositionData::set_altitude(std::int64_t altitudeToSet) + { + bool retVal = (altitude != altitudeToSet); + altitude = altitudeToSet; + return retVal; + } + + std::int64_t GNSSPositionData::get_raw_latitude() const + { + return latitude; + } + + double GNSSPositionData::get_latitude() const + { + return (static_cast(latitude) * 1E-16); + } + + bool GNSSPositionData::set_latitude(std::int64_t latitudeToSet) + { + bool retVal = (latitude != latitudeToSet); + latitude = latitudeToSet; + return retVal; + } + + std::int64_t GNSSPositionData::get_raw_longitude() const + { + return longitude; + } + + double GNSSPositionData::get_longitude() const + { + return (static_cast(longitude) * 1E-16); + } + + bool GNSSPositionData::set_longitude(std::int64_t longitudeToSet) + { + bool retVal = (longitude != longitudeToSet); + longitude = longitudeToSet; + return retVal; + } + + std::int32_t GNSSPositionData::get_raw_geoidal_separation() const + { + return geoidalSeparation; + } + + float GNSSPositionData::get_geoidal_separation() const + { + return (geoidalSeparation * 0.01f); + } + + bool GNSSPositionData::set_geoidal_separation(std::int32_t separation) + { + bool retVal = (geoidalSeparation != separation); + geoidalSeparation = separation; + return retVal; + } + + std::uint32_t GNSSPositionData::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool GNSSPositionData::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::uint8_t GNSSPositionData::get_sequence_id() const + { + return sequenceID; + } + + bool GNSSPositionData::set_sequence_id(std::uint8_t sequenceNumber) + { + bool retVal = (sequenceNumber != sequenceID); + sequenceID = sequenceNumber; + return retVal; + } + + GNSSPositionData::TypeOfSystem GNSSPositionData::get_type_of_system() const + { + return systemType; + } + + bool GNSSPositionData::set_type_of_system(TypeOfSystem type) + { + bool retVal = (systemType != type); + systemType = type; + return retVal; + } + + GNSSPositionData::GNSSMethod GNSSPositionData::get_gnss_method() const + { + return method; + } + + bool GNSSPositionData::set_gnss_method(GNSSMethod gnssFixMethod) + { + bool retVal = (method != gnssFixMethod); + method = gnssFixMethod; + return retVal; + } + + GNSSPositionData::Integrity GNSSPositionData::get_integrity() const + { + return integrityChecking; + } + + bool GNSSPositionData::set_integrity(Integrity integrity) + { + bool retVal = (integrityChecking != integrity); + integrityChecking = integrity; + return retVal; + } + + std::uint8_t GNSSPositionData::get_number_of_space_vehicles() const + { + return numberOfSpaceVehicles; + } + + bool GNSSPositionData::set_number_of_space_vehicles(std::uint8_t numberOfSVs) + { + bool retVal = (numberOfSpaceVehicles != numberOfSVs); + numberOfSpaceVehicles = numberOfSVs; + return retVal; + } + + std::int16_t GNSSPositionData::get_raw_horizontal_dilution_of_precision() const + { + return horizontalDilutionOfPrecision; + } + + float GNSSPositionData::get_horizontal_dilution_of_precision() const + { + return (horizontalDilutionOfPrecision * 0.01f); + } + + bool GNSSPositionData::set_horizontal_dilution_of_precision(std::int16_t hdop) + { + bool retVal = (horizontalDilutionOfPrecision != hdop); + horizontalDilutionOfPrecision = hdop; + return retVal; + } + + std::int16_t GNSSPositionData::get_raw_positional_dilution_of_precision() const + { + return positionalDilutionOfPrecision; + } + + float GNSSPositionData::get_positional_dilution_of_precision() const + { + return (positionalDilutionOfPrecision * 0.01f); + } + + bool GNSSPositionData::set_positional_dilution_of_precision(std::int16_t pdop) + { + bool retVal = (positionalDilutionOfPrecision != pdop); + positionalDilutionOfPrecision = pdop; + return retVal; + } + + std::uint8_t GNSSPositionData::get_number_of_reference_stations() const + { + return referenceStations.size(); + } + + bool GNSSPositionData::set_number_of_reference_stations(std::uint8_t stations) + { + bool retVal = (referenceStations.size() != stations); + referenceStations.resize(stations); + return retVal; + } + + std::uint16_t GNSSPositionData::get_reference_station_id(std::size_t index) const + { + std::uint16_t retVal = 0; + + if (index < referenceStations.size()) + { + retVal = referenceStations.at(index).stationID; + } + return retVal; + } + + std::uint16_t GNSSPositionData::get_raw_reference_station_corrections_age(std::size_t index) const + { + std::uint16_t retVal = 0; + + if (index < referenceStations.size()) + { + retVal = referenceStations.at(index).ageOfDGNSSCorrections; + } + return retVal; + } + + float GNSSPositionData::get_reference_station_corrections_age(std::size_t index) const + { + return (get_raw_reference_station_corrections_age(index) * 0.01f); + } + + GNSSPositionData::TypeOfSystem GNSSPositionData::get_reference_station_system_type(std::size_t index) const + { + TypeOfSystem retVal = TypeOfSystem::Null; + + if (index < referenceStations.size()) + { + retVal = referenceStations.at(index).stationType; + } + return retVal; + } + + bool GNSSPositionData::set_reference_station(std::size_t index, std::uint16_t ID, TypeOfSystem type, std::uint16_t ageOfCorrections) + { + bool retVal = false; + + if (index < referenceStations.size()) + { + retVal |= referenceStations.at(index).ageOfDGNSSCorrections != ageOfCorrections; + retVal |= referenceStations.at(index).stationID != ID; + retVal |= referenceStations.at(index).stationType != type; + referenceStations.at(index) = ReferenceStationData(ID, type, ageOfCorrections); + } + return retVal; + } + + std::uint16_t GNSSPositionData::get_position_date() const + { + return positionDate; + } + + bool GNSSPositionData::set_position_date(std::uint16_t dateToSet) + { + bool retVal = (positionDate != dateToSet); + positionDate = dateToSet; + return retVal; + } + + std::uint32_t GNSSPositionData::get_raw_position_time() const + { + return positionTime; + } + + double GNSSPositionData::get_position_time() const + { + return 1E-04 * positionTime; + } + + bool GNSSPositionData::set_position_time(std::uint32_t timeToSet) + { + bool retVal = (positionTime != timeToSet); + positionTime = timeToSet; + return retVal; + } + + void GNSSPositionData::serialize(std::vector &buffer) const + { + buffer.resize(MINIMUM_LENGTH_BYTES); + + buffer.at(0) = sequenceID; + buffer.at(1) = static_cast(positionDate & 0xFF); + buffer.at(2) = static_cast((positionDate >> 8) & 0xFF); + buffer.at(3) = static_cast(positionTime & 0xFF); + buffer.at(4) = static_cast((positionTime >> 8) & 0xFF); + buffer.at(5) = static_cast((positionTime >> 16) & 0xFF); + buffer.at(6) = static_cast((positionTime >> 24) & 0xFF); + buffer.at(7) = static_cast(latitude & 0xFF); + buffer.at(8) = static_cast((latitude >> 8) & 0xFF); + buffer.at(9) = static_cast((latitude >> 16) & 0xFF); + buffer.at(10) = static_cast((latitude >> 24) & 0xFF); + buffer.at(11) = static_cast((latitude >> 32) & 0xFF); + buffer.at(12) = static_cast((latitude >> 40) & 0xFF); + buffer.at(13) = static_cast((latitude >> 48) & 0xFF); + buffer.at(14) = static_cast((latitude >> 56) & 0xFF); + buffer.at(15) = static_cast(longitude & 0xFF); + buffer.at(16) = static_cast((longitude >> 8) & 0xFF); + buffer.at(17) = static_cast((longitude >> 16) & 0xFF); + buffer.at(18) = static_cast((longitude >> 24) & 0xFF); + buffer.at(19) = static_cast((longitude >> 32) & 0xFF); + buffer.at(20) = static_cast((longitude >> 40) & 0xFF); + buffer.at(21) = static_cast((longitude >> 48) & 0xFF); + buffer.at(22) = static_cast((longitude >> 56) & 0xFF); + buffer.at(23) = static_cast(altitude & 0xFF); + buffer.at(24) = static_cast((altitude >> 8) & 0xFF); + buffer.at(25) = static_cast((altitude >> 16) & 0xFF); + buffer.at(26) = static_cast((altitude >> 24) & 0xFF); + buffer.at(27) = static_cast((altitude >> 32) & 0xFF); + buffer.at(28) = static_cast((altitude >> 40) & 0xFF); + buffer.at(29) = static_cast((altitude >> 48) & 0xFF); + buffer.at(30) = static_cast((altitude >> 56) & 0xFF); + buffer.at(31) = (static_cast(systemType) & 0x0F); + buffer.at(31) |= ((static_cast(method) & 0x0F) << 4); + buffer.at(32) = (static_cast(integrityChecking) | 0xFC); + buffer.at(33) = numberOfSpaceVehicles; + buffer.at(34) = static_cast(horizontalDilutionOfPrecision & 0xFF); + buffer.at(35) = static_cast((horizontalDilutionOfPrecision >> 8) & 0xFF); + buffer.at(36) = static_cast(positionalDilutionOfPrecision & 0xFF); + buffer.at(37) = static_cast((positionalDilutionOfPrecision >> 8) & 0xFF); + buffer.at(38) = static_cast(geoidalSeparation & 0xFF); + buffer.at(39) = static_cast((geoidalSeparation >> 8) & 0xFF); + buffer.at(40) = static_cast((geoidalSeparation >> 16) & 0xFF); + buffer.at(41) = static_cast((geoidalSeparation >> 24) & 0xFF); + buffer.at(42) = get_number_of_reference_stations(); + + for (std::uint8_t i = 0; i < get_number_of_reference_stations(); i++) + { + buffer.push_back((static_cast(referenceStations.at(i).stationType) & 0x0F) | + ((referenceStations.at(i).stationID & 0x0F) << 4)); + buffer.push_back(static_cast(referenceStations.at(i).stationID >> 4)); + buffer.push_back(static_cast(referenceStations.at(i).ageOfDGNSSCorrections & 0xFF)); + buffer.push_back(static_cast((referenceStations.at(i).ageOfDGNSSCorrections >> 8) & 0xFF)); + } + } + + bool GNSSPositionData::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (receivedMessage.get_data_length() >= MINIMUM_LENGTH_BYTES) + { + retVal = set_sequence_id(receivedMessage.get_uint8_at(0)); + retVal |= set_position_date(receivedMessage.get_uint16_at(1)); + retVal |= set_position_time(receivedMessage.get_uint32_at(3)); + retVal |= set_latitude(receivedMessage.get_int64_at(7)); + retVal |= set_longitude(receivedMessage.get_int64_at(15)); + retVal |= set_altitude(receivedMessage.get_int64_at(23)); + retVal |= set_type_of_system(static_cast(receivedMessage.get_uint8_at(31) & 0x0F)); + retVal |= set_gnss_method(static_cast((receivedMessage.get_uint8_at(31) >> 4) & 0x0F)); + retVal |= set_integrity(static_cast(receivedMessage.get_uint8_at(32) & 0x03)); + retVal |= set_number_of_space_vehicles(receivedMessage.get_uint8_at(33)); + retVal |= set_horizontal_dilution_of_precision(receivedMessage.get_int16_at(34)); + retVal |= set_positional_dilution_of_precision(receivedMessage.get_int16_at(36)); + retVal |= set_geoidal_separation(receivedMessage.get_int32_at(38)); + + referenceStations.clear(); + retVal |= set_number_of_reference_stations(receivedMessage.get_uint8_at(42)); + + for (std::uint8_t i = 0; i < get_number_of_reference_stations(); i++) + { + if (receivedMessage.get_data_length() >= static_cast(MINIMUM_LENGTH_BYTES + (i * 4))) + { + referenceStations.at(i) = ReferenceStationData((receivedMessage.get_uint16_at(MINIMUM_LENGTH_BYTES + (i * 4)) >> 4), + static_cast(receivedMessage.get_uint8_at(MINIMUM_LENGTH_BYTES + (i * 4)) & 0x0F), + receivedMessage.get_uint16_at(2 + MINIMUM_LENGTH_BYTES + (i * 4))); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't fully parse GNSS position data reference station info because message length is not long enough."); + break; + } + } + } + else + { + CANStackLogger::warn("[NMEA2K]: Cannot deserialize GNSS position data. DLC must be >= 43 bytes."); + } + return retVal; + } + + std::uint32_t GNSSPositionData::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + + GNSSPositionData::ReferenceStationData::ReferenceStationData(std::uint16_t id, TypeOfSystem type, std::uint16_t age) : + stationID(id), + stationType(type), + ageOfDGNSSCorrections(age) + { + } + + Datum::Datum(std::shared_ptr source) : + senderControlFunction(source) + { + referenceDatum.resize(DATUM_STRING_LENGTHS); + localDatum.resize(DATUM_STRING_LENGTHS); + } + + std::shared_ptr Datum::get_control_function() const + { + return senderControlFunction; + } + + std::uint32_t Datum::get_timestamp() const + { + return messageTimestamp_ms; + } + + bool Datum::set_timestamp(std::uint32_t timestamp) + { + bool retVal = (messageTimestamp_ms != timestamp); + messageTimestamp_ms = timestamp; + return retVal; + } + + std::string Datum::get_local_datum() const + { + return localDatum; + } + + bool Datum::set_local_datum(const std::string &datum) + { + bool retVal = (datum != localDatum); + localDatum = datum; + + if (localDatum.length() != DATUM_STRING_LENGTHS) + { + localDatum.resize(DATUM_STRING_LENGTHS); + } + return retVal; + } + + std::string Datum::get_reference_datum() const + { + return referenceDatum; + } + + bool Datum::set_reference_datum(const std::string &datum) + { + bool retVal = (datum != referenceDatum); + referenceDatum = datum; + + if (referenceDatum.length() != DATUM_STRING_LENGTHS) + { + referenceDatum.resize(DATUM_STRING_LENGTHS); + } + return retVal; + } + + std::int32_t Datum::get_raw_delta_latitude() const + { + return deltaLatitude; + } + + double Datum::get_delta_latitude() const + { + return (static_cast(deltaLatitude) * 1E-7); + } + + bool Datum::set_delta_latitude(std::int32_t delta) + { + bool retVal = (deltaLatitude != delta); + deltaLatitude = delta; + return retVal; + } + + double Datum::get_delta_longitude() const + { + return (static_cast(deltaLongitude) * 1E-7); + } + + std::int32_t Datum::get_raw_delta_longitude() const + { + return deltaLongitude; + } + + bool Datum::set_delta_longitude(std::int32_t delta) + { + bool retVal = (deltaLongitude != delta); + deltaLongitude = delta; + return retVal; + } + + std::int32_t Datum::get_raw_delta_altitude() const + { + return deltaAltitude; + } + + float Datum::get_delta_altitude() const + { + return (1E-2f * deltaAltitude); + } + + bool Datum::set_delta_altitude(std::int32_t delta) + { + bool retVal = (deltaAltitude != delta); + deltaAltitude = delta; + return retVal; + } + + void Datum::serialize(std::vector &buffer) const + { + buffer.resize(LENGTH_BYTES); + + buffer.at(0) = localDatum.at(0); + buffer.at(1) = localDatum.at(1); + buffer.at(2) = localDatum.at(2); + buffer.at(3) = localDatum.at(3); + buffer.at(4) = static_cast(deltaLatitude & 0xFF); + buffer.at(5) = static_cast((deltaLatitude >> 8) & 0xFF); + buffer.at(6) = static_cast((deltaLatitude >> 16) & 0xFF); + buffer.at(7) = static_cast((deltaLatitude >> 24) & 0xFF); + buffer.at(8) = static_cast(deltaLongitude & 0xFF); + buffer.at(9) = static_cast((deltaLongitude >> 8) & 0xFF); + buffer.at(10) = static_cast((deltaLongitude >> 16) & 0xFF); + buffer.at(11) = static_cast((deltaLongitude >> 24) & 0xFF); + buffer.at(12) = static_cast(deltaAltitude & 0xFF); + buffer.at(13) = static_cast((deltaAltitude >> 8) & 0xFF); + buffer.at(14) = static_cast((deltaAltitude >> 16) & 0xFF); + buffer.at(15) = static_cast((deltaAltitude >> 24) & 0xFF); + buffer.at(16) = referenceDatum.at(0); + buffer.at(17) = referenceDatum.at(1); + buffer.at(18) = referenceDatum.at(2); + buffer.at(19) = referenceDatum.at(3); + } + + bool Datum::deserialize(const CANMessage &receivedMessage) + { + bool retVal = false; + + if (receivedMessage.get_data_length() >= LENGTH_BYTES) + { + std::string tempString; + tempString.push_back(static_cast(receivedMessage.get_uint8_at(0))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(1))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(2))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(3))); + retVal = set_local_datum(tempString); + retVal |= set_delta_latitude(receivedMessage.get_int32_at(4)); + retVal |= set_delta_longitude(receivedMessage.get_int32_at(8)); + retVal |= set_delta_altitude(receivedMessage.get_int32_at(12)); + tempString.clear(); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(16))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(17))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(18))); + tempString.push_back(static_cast(receivedMessage.get_uint8_at(19))); + retVal |= set_reference_datum(tempString); + } + else + { + CANStackLogger::warn("[NMEA2K]: Can't deserialize Datum message. Message length must be at least 20 bytes."); + } + return retVal; + } + + std::uint32_t Datum::get_timeout() + { + return CYCLIC_MESSAGE_RATE_MS; + } + } +} diff --git a/src/nmea2000_message_definitions.hpp b/src/nmea2000_message_definitions.hpp new file mode 100644 index 0000000..ed95c82 --- /dev/null +++ b/src/nmea2000_message_definitions.hpp @@ -0,0 +1,880 @@ +//================================================================================================ +/// @file nmea2000_message_definitions.hpp +/// +/// @brief This file contains class definitions that will comprise the individual components +/// of the NMEA2000 message interface for the stack. Generally this separation exists to keep +/// the file size of nmea2000_message_interface.hpp/cpp smaller. +/// +/// @note This library and its authors are not affiliated with the National Marine +/// Electronics Association in any way. +/// +/// @author Adrian Del Grosso +/// +/// @copyright 2023 Adrian Del Grosso +//================================================================================================ +#ifndef NMEA2000_MESSAGE_DEFINITIONS_HPP +#define NMEA2000_MESSAGE_DEFINITIONS_HPP + +#include "can_internal_control_function.hpp" + +#include + +namespace isobus +{ + /// @brief A namespace for generic NMEA2000 message definitions + namespace NMEA2000Messages + { + constexpr std::uint8_t MAX_SEQUENCE_ID = 252; ///< The max non-special allowable value of a NMEA2K sequence ID + + /// @brief Represents the data sent in the NMEA2K PGN 127250 (0x1F112) + class VesselHeading + { + public: + /// @brief The reference which the vessel heading is relative to + enum class HeadingSensorReference : std::uint8_t + { + True = 0, ///< True North + Magnetic = 1, ///< Magnetic North + Error = 2, + NotApplicableOrNull = 3 + }; + + /// @brief Constructor for a VesselHeading message data object + /// @param[in] source The control function sending this message + explicit VesselHeading(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns true if the value that was set was different from the stored value + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Returns the vessel heading in units of 0.0001 radians, which are the message's base units + /// @returns Vessel heading in units of 0.0001 radians + std::uint16_t get_raw_heading() const; + + /// @brief Returns the vessel heading in radians + /// @returns Vessel heading in radians + float get_heading() const; + + /// @brief Sets the vessel heading + /// @param[in] heading The heading to set in 0.0001 radians + /// @returns True if the value that was set was different from the stored value + bool set_heading(std::uint16_t heading); + + /// @brief Returns the magnetic deviation in 0.0001 radians + /// @returns The magnetic deviation in 0.0001 radians + std::int16_t get_raw_magnetic_deviation() const; + + /// @brief Returns the magnetic deviation in radians + /// @returns The magnetic deviation in radians + float get_magnetic_deviation() const; + + /// @brief Sets the magnetic deviation in 0.0001 radians + /// @param[in] deviation The magnetic deviation to set, in units of 0.0001 radians + /// @returns true if the value that was set was different from the stored value + bool set_magnetic_deviation(std::int16_t deviation); + + /// @brief Returns the magnetic variation in units of 0.0001 radians + /// @returns The magnetic variation in units of 0.0001 radians + std::int16_t get_raw_magnetic_variation() const; + + /// @brief Returns the magnetic variation in units of radians + /// @returns The magnetic variation in units of radians + float get_magnetic_variation() const; + + /// @brief Sets the magnetic variation, in units of 0.0001 radians + /// @param[in] variation The magnetic variation to set, in units of 0.0001 radians + /// @returns true if the value that was set was different from the stored value + bool set_magnetic_variation(std::int16_t variation); + + /// @brief Returns the sequence ID. This is used to associate data within other PGNs with this message. + /// @returns The sequence ID for this message + std::uint8_t get_sequence_id() const; + + /// @brief Sets the sequence ID for this message. + /// @param[in] sequenceNumber The sequence number to set. Max value is 252. + /// @returns true if the value that was set was different from the stored value + bool set_sequence_id(std::uint8_t sequenceNumber); + + /// @brief Returns the reference to which the reported heading is relative to + /// @returns The reference to which the reported heading is relative to + HeadingSensorReference get_sensor_reference() const; + + /// @brief Sets the reference to which the reported heading is relative to + /// @param[in] reference The reference to set + /// @returns true if the value that was set was different from the stored value + bool set_sensor_reference(HeadingSensorReference reference); + + /// @brief Takes the current state of the object and serializes it into a buffer to be sent. + /// @param[in] buffer A vector to populate with the message data + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 100; ///< The interval in milliseconds on which this message should be sent/received + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + std::uint16_t headingReading = 0; ///< The raw heading in 0.0001 radians, relative to the indicated HeadingSensorReference. + std::int16_t magneticDeviation = 0; ///< The magnetic deviation if not included in the reading in 0.0001 radians. Positive values are easterly. + std::int16_t magneticVariation = 0; ///< The magnetic variation if applicable in 0.0001 radians. Positive values are easterly. If the reference is magnetic, you can add this to the heading to get data relative to true north. + std::uint8_t sequenceID = 0; ///< The sequence identifier field is used to tie related PGNs together. Somewhat arbitrary. + HeadingSensorReference sensorReference = HeadingSensorReference::NotApplicableOrNull; ///< Indicates what the heading is relative to, ie true or magnetic north + }; + + /// @brief Represents the data sent in the NMEA2K PGN 127251 (0x1F113) + class RateOfTurn + { + public: + /// @brief Constructor for a RateOfTurn message data object + /// @param[in] source The control function sending the message + explicit RateOfTurn(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns true if the value that was set was different from the stored value + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Returns the rate of turn of the vessel/vehicle in units of 1/32 x 10E-6 rad/s + /// @returns The rate of turn of the vessel/vehicle in units of 1/32 x 10E-6 rad/s + std::int32_t get_raw_rate_of_turn() const; + + /// @brief Returns the rate of turn of the vessel/vehicle in rad/s + /// @returns The rate of turn of the vessel/vehicle in rad/s + double get_rate_of_turn() const; + + /// @brief Sets the rate of turn in units of 1/32 x 10E-6 rad/s + /// @param[in] turnRate The rate of turn to set, in units of 1/32 x 10E-6 rad/s + /// @returns true if the value that was set was different from the stored value + bool set_rate_of_turn(std::int32_t turnRate); + + /// @brief Returns the sequence ID. This is used to associate data within other PGNs with this message. + /// @returns The sequence ID for this message + std::uint8_t get_sequence_id() const; + + /// @brief Sets the sequence ID for this message. + /// @param[in] sequenceNumber The sequence number to set. Max value is 252. + /// @returns true if the value that was set was different from the stored value + bool set_sequence_id(std::uint8_t sequenceNumber); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 100; ///< The interval in milliseconds on which this message should be sent/received + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + std::int32_t rateOfTurn = 0; ///< The rate of turn in 1/32 * 10e-6 rad/s. Positive values indicate turning right (starboard) relative to the vehicle's reference point. + std::uint8_t sequenceID = 0; ///< The sequence identifier field is used to tie related PGNs together. Somewhat arbitrary. + }; + + /// @brief Represents the data sent in the NMEA2K PGN 129025 (0x1F801) + class PositionRapidUpdate + { + public: + /// @brief Constructor for a PositionRapidUpdate message data object + /// @param[in] source The control function sending this message + explicit PositionRapidUpdate(std::shared_ptr source); + + static constexpr std::int32_t NOT_AVAILABLE = 0x7FFFFFFF; ///< A generic value that may be reported if the position solution is invalid + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns true if the value that was set was different from the stored value + bool set_timestamp(std::uint32_t timestamp); + + /// @attention This is MUCH less accurate than the position in PGN 1F805 (129029). Use that instead if present. + /// @returns The current vessel/vehicle latitude in 1*10E-7 degrees + std::int32_t get_raw_latitude() const; + + /// @attention This is MUCH less accurate than the position in PGN 1F805 (129029). Use that instead if present. + /// @returns The current vessel/vehicle longitude in 1*10E-7 degrees + double get_latitude() const; + + /// @brief Sets the current latitude in units of 1*10E-7 degrees + /// @param[in] latitudeToSet The latitude to set in units of 1*10E-7 degrees + /// @returns true if the value that was set was different from the stored value + bool set_latitude(std::int32_t latitudeToSet); + + /// @attention This is MUCH less accurate than the position in PGN 1F805 (129029). Use that instead if present. + /// @returns The current vessel/vehicle longitude in 1*10E-7 degrees + std::int32_t get_raw_longitude() const; + + /// @attention This is MUCH less accurate than the position in PGN 1F805 (129029). Use that instead if present. + /// @returns The current vessel/vehicle longitude in 1*10E-7 degrees + double get_longitude() const; + + /// @brief Sets the current longitude in units of 1*10E-7 degrees + /// @param[in] longitudeToSet The latitude to set in units of 1*10E-7 degrees + /// @returns true if the value that was set was different from the stored value + bool set_longitude(std::int32_t longitudeToSet); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 100; ///< The transmit interval for this message as specified in NMEA2000 + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::int32_t latitude = NOT_AVAILABLE; ///< The latitude in 1*10E-7 degrees. Negative values indicate south latitudes. + std::int32_t longitude = NOT_AVAILABLE; ///< The longitude in 1*10E-7 degrees. Negative values indicate west longitudes. + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + }; + + /// @brief Represents the data sent in the NMEA2K PGN 129026 (0x1F802) + class CourseOverGroundSpeedOverGroundRapidUpdate + { + public: + /// @brief Enumerates the references to which the course may be relative to + enum class CourseOverGroundReference : std::uint8_t + { + True = 0, ///< True north + Magnetic = 1, ///< Magnetic North + Error = 2, + NotApplicableOrNull = 3 + }; + + /// @brief Constructor for a CourseOverGroundSpeedOverGroundRapidUpdate message data object + /// @param[in] source The control function sending/receiving this message + explicit CourseOverGroundSpeedOverGroundRapidUpdate(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Returns the course over ground in its base units of 0.0001 radians (between 0 and 2 pi radians) + /// @returns The course over ground in its base units of 0.0001 radians + std::uint16_t get_raw_course_over_ground() const; + + /// @brief Returns the course over ground in units of radians + /// @returns Course over ground in units of radians + float get_course_over_ground() const; + + /// @brief Sets the course over ground in units of 0.0001 radians + /// @param[in] course The course to set, in 0.0001 radians + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_course_over_ground(std::uint16_t course); + + /// @brief Returns the speed over ground in units of 0.01 meters per second + /// @returns The speed over ground in units of 0.01 meters per second + std::uint16_t get_raw_speed_over_ground() const; + + /// @brief Returns the speed over ground in units of meters per second + /// @returns The speed over ground in units of meters per second + float get_speed_over_ground() const; + + /// @brief Sets the speed over ground in units of 0.01 meters per second + /// @param[in] speed The speed to set, in 0.01 m/s + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_speed_over_ground(std::uint16_t speed); + + /// @brief Returns the sequence ID. This is used to associate data within other PGNs with this message. + /// @returns The sequence ID for this message + std::uint8_t get_sequence_id() const; + + /// @brief Sets the sequence ID for this message. + /// @param[in] sequenceNumber The sequence number to set. Max value is 252. + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_sequence_id(std::uint8_t sequenceNumber); + + /// @brief Returns the reference to which the course over ground is relative + /// @returns The reference to which the course is relative + CourseOverGroundReference get_course_over_ground_reference() const; + + /// @brief Sets the reference to which the course over ground is relative + /// @param[in] reference The reference to set (as enumerated in CourseOverGroundReference) + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_course_over_ground_reference(CourseOverGroundReference reference); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 250; ///< The transmit interval for this message as specified in NMEA2000 + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + std::uint16_t courseOverGround = 0; ///< This field contains the direction of the path over ground actually followed by the vessel in 0.0001 radians between 0 and 2pi rad. + std::uint16_t speedOverGround = 0; ///< This field contains the speed of the vessel in 0.01 m/s + std::uint8_t sequenceID = 0; ///< The sequence identifier field is used to tie related PGNs together. Somewhat arbitrary. + CourseOverGroundReference cogReference = CourseOverGroundReference::NotApplicableOrNull; ///< Used to indicate the reference for the course over ground, ie true or magnetic north + }; + + /// @brief This message is a way for a GNSS receiver to provide a current position without using fast packet based on + /// The content of the last position data combined from the GNSS Position Data message and any prior position delta messages. + /// This PGN provides latitude and longitude referenced to WGS84. + class PositionDeltaHighPrecisionRapidUpdate + { + public: + /// @brief Constructor for a PositionDeltaHighPrecisionRapidUpdate message data object + /// @param[in] source The control function sending this message + explicit PositionDeltaHighPrecisionRapidUpdate(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Returns the latitude delta relative to our last position in 1x10E-16 degrees + /// @returns Latitude delta relative to our last position in 1x10E-16 degrees + std::int32_t get_raw_latitude_delta() const; + + /// @brief Returns the latitude delta relative to our last position in degrees + /// @returns Latitude delta relative to our last position in degrees + double get_latitude_delta() const; + + /// @brief Sets the current latitude delta in units of 1x10E-16 degrees + /// @param[in] delta Latitude delta to set in units of 1x10E-16 degrees + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_latitude_delta(std::int32_t delta); + + /// @brief Returns the longitude delta relative to our last position in 1x10E-16 degrees + /// @returns Longitude delta relative to our last position in 1x10E-16 degrees + std::int32_t get_raw_longitude_delta() const; + + /// @brief Returns the longitude delta relative to our last position in degrees + /// @returns Longitude delta relative to our last position in degrees + double get_longitude_delta() const; + + /// @brief Sets the current longitude delta relative to our last position in 1x10E-16 degrees + /// @param[in] delta Longitude delta to set in units of 1x10E-16 degrees + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_longitude_delta(std::int32_t delta); + + /// @brief Returns the sequence ID. This is used to associate data within other PGNs with this message. + /// @returns The sequence ID for this message + std::uint8_t get_sequence_id() const; + + /// @brief Sets the sequence ID for this message. + /// @param[in] sequenceNumber The sequence number to set. Max value is 252. + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_sequence_id(std::uint8_t sequenceNumber); + + /// @brief Returns the raw time delta since the last reported time in 5x10e-3 seconds + /// @returns Time delta in units of 5x10e-3 seconds + std::uint8_t get_raw_time_delta() const; + + /// @brief Returns the raw time delta since the last reported time in seconds + /// @returns Time delta in units of seconds + double get_time_delta() const; + + /// @brief Sets the time delta, in units of 5x10e-3 seconds + /// @param[in] delta The time delta to set in units of 5x10e-3 seconds + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_time_delta(std::uint8_t delta); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 250; ///< The transmit interval for this message as specified in NMEA2000 + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + std::int32_t latitudeDelta = 0; ///< The latitude delta in 1x10E-16 degrees + std::int32_t longitudeDelta = 0; ///< The longitude delta in 1x10E-16 degrees + std::uint8_t sequenceID = 0; ///< The sequence identifier field is used to tie related PGNs together. In this case, ties back to GNSS Position Data sequence ID most likely. + std::uint8_t timeDelta = 0; ///< The time delta in 5x10e-3 seconds + }; + + /// @brief Represents the data sent in the NMEA2K PGN 129029 (0x1F805) + class GNSSPositionData + { + public: + /// @brief Enumerates the different GNSS systems that can be reported in this message + enum class TypeOfSystem + { + GPS = 0x00, ///< A GNSS system operated by the United States military + GLONASS = 0x01, ///< A Russian state operated alternative to GPS + GPSPlusGLONASS = 0x02, ///< A system using both GPS and GLONASS + GPSPlusSBAS = 0x03, ///< Satellite Based Augmentation System (WAAS) enhanced GPS (Run by the US Federal Aviation Administration) + GPSPlusSBASPlusGLONASS = 0x04, ///< A system using SBAS augmented GPS as well as GLONASS + Chayka = 0x05, ///< A Russian Hyperbolic Radio Navigation System similar to Loran-C + Integrated = 0x06, ///< Using internally integrated solution (maybe digital dead reckoning) + Surveyed = 0x07, + Galileo = 0x08, ///< A GNSS system operated by the European Space Agency + Null = 0x0F + }; + + /// @brief Enumerates the GNSS methods that can be reported in this message + enum class GNSSMethod + { + NoGNSS = 0x00, ///< Either there is not enough data to compute a navigation solution, or the computed solution is outside of the acceptable error criteria + GNSSFix = 0x01, ///< Position solution has been achieved + DGNSSFix = 0x02, ///< Differential solution achieved based on deviation from a well known reference point + PreciseGNSS = 0x03, ///< Solution achieved using Precise Point Positioning (PPP) + RTKFixedInteger = 0x04, ///< Solution achieved using radio corrections (from an RTK base station) + RTKFloat = 0x05, ///< Solution achieved using radio corrections (from an RTK base station) but using floating point instead of fixed integers + EstimatedMode = 0x06, ///< Dead reckoning + ManualInput = 0x07, + SimulateMode = 0x08, + Null = 0x0F + }; + + /// @brief Enumerates the integrity checking modes that can be reported in this message. You will most often see "NoIntegrityChecking" in reality. + enum class Integrity + { + NoIntegrityChecking = 0x00, + Safe = 0x01, + Caution = 0x02, + Unsafe = 0x03 + }; + + /// @brief Constructor for a GNSSPositionData message data object + /// @param[in] source The control function sending this message + explicit GNSSPositionData(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns the altitude portion of the position fix in its base units of 1x10E-6 meters. Range is +/- 9.223 x 10E+12 meters + /// @returns Altitude portion of the position fix in its base units of 1x10E-6 meters. Range is +/- 9.223 x 10E+12 meters + std::int64_t get_raw_altitude() const; + + /// @brief Returns the altitude portion of the position fix in scaled units of meters. Range is +/- 9.223 x 10E+12 meters + /// @returns Altitude portion of the position fix in scaled units of meters. Range is +/- 9.223 x 10E+12 meters + double get_altitude() const; + + /// @brief Sets the reported altitude in units of 1x10E-6 meters. Range is +/- 9.223 x 10E+12 meters + /// @param[in] altitudeToSet Altitude to set in units of 1x10E-6 meters. Range is +/- 9.223 x 10E+12 meters + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_altitude(std::int64_t altitudeToSet); + + /// @brief Returns our current position's latitude in its base units of 1x10E-16 degrees + /// @returns Current position's latitude in units of 1x10E-16 degrees + std::int64_t get_raw_latitude() const; + + /// @brief Returns our current position's latitude in units of degrees + /// @returns Current position's latitude in units of degrees + double get_latitude() const; + + /// @brief Sets the reported latitude in its base units of 1x10E-16 degrees + /// @param[in] latitudeToSet The latitude to set in 1x10E-16 degrees + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_latitude(std::int64_t latitudeToSet); + + /// @brief Returns our current position's longitude in its base units of 1x10E-16 degrees + /// @returns Current position's longitude in units of 1x10E-16 degrees + std::int64_t get_raw_longitude() const; + + /// @brief Returns our current position's longitude in units of degrees + /// @returns Current position's longitude in units of degrees + double get_longitude() const; + + /// @brief Sets the reported longitude in its base units of 1x10E-16 degrees + /// @param[in] longitudeToSet The longitude to set in 1x10E-16 degrees + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_longitude(std::int64_t longitudeToSet); + + /// @brief Returns the geoidal separation in units of 0.01 meters + /// @details This returns the difference between the earth ellipsoid and mean-sea-level (geoid) defined by the reference datum + /// @returns The geoidal separation in units of 0.01m + std::int32_t get_raw_geoidal_separation() const; + + /// @brief Returns the geoidal separation in units of meters + /// @details This returns the difference between the earth ellipsoid and mean-sea-level (geoid) defined by the reference datum + /// @returns The geoidal separation in units of meters + float get_geoidal_separation() const; + + /// @brief Sets the geoidal separation + /// @details This value is the difference between the earth ellipsoid and mean-sea-level (geoid) defined by the reference datum + /// @param[in] separation The geoidal separation to set + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_geoidal_separation(std::int32_t separation); + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Returns the sequence ID. This is used to associate data within other PGNs with this message. + /// @returns The sequence ID for this message + std::uint8_t get_sequence_id() const; + + /// @brief Sets the sequence ID for this message. + /// @param[in] sequenceNumber The sequence number to set. Max value is 252. + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_sequence_id(std::uint8_t sequenceNumber); + + /// @brief Returns the reported type of GNSS system that produced this position solution + /// @returns The type of GNSS system that produced this position solution + TypeOfSystem get_type_of_system() const; + + /// @brief Sets the reported type of GNSS system that produced this position solution + /// @param[in] type The type of system to set + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_type_of_system(TypeOfSystem type); + + /// @brief Returns the GNSS method being reported as part of this position solution, such as RTK Float or DGNSS + /// @returns The GNSS method being reported as part of this position solution, such as RTK Float or DGNSS + GNSSMethod get_gnss_method() const; + + /// @brief Sets the GNSS method to report as the source of this position solution, such as RTK float or DGNSS + /// @param[in] gnssFixMethod The GNSS method to report as the source of this position solution + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_gnss_method(GNSSMethod gnssFixMethod); + + /// @brief Sets the integrity being reported for this position solution if applicable + /// @returns The integrity being reported for this position solution + Integrity get_integrity() const; + + /// @brief Sets the integrity reported for this position solution + /// @param[in] integrity The integrity to report + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_integrity(Integrity integrity); + + /// @brief Returns the number of space vehicles used in this position solution + /// @returns The number of space vehicles used in this position solution + std::uint8_t get_number_of_space_vehicles() const; + + /// @brief Sets the number of space vehicles in view and used in this position solution + /// @param[in] numberOfSVs The number of space vehicles to set + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_number_of_space_vehicles(std::uint8_t numberOfSVs); + + /// @brief Returns the HDOP for this solution. + /// This Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + /// @returns The horizontal dilution of precision (HDOP) + std::int16_t get_raw_horizontal_dilution_of_precision() const; + + /// @brief Returns the HDOP for this solution. + /// This Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + /// @returns The horizontal dilution of precision (HDOP) + float get_horizontal_dilution_of_precision() const; + + /// @brief Sets the horizontal dilution of precision (HDOP) + /// @param[in] hdop The positional dilution of precision to set + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_horizontal_dilution_of_precision(std::int16_t hdop); + + /// @brief Returns the PDOP for this solution. + /// This Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + /// @returns The positional dilution of precision (PDOP) + std::int16_t get_raw_positional_dilution_of_precision() const; + + /// @brief Returns the PDOP for this solution. + /// This Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + /// @returns The positional dilution of precision (PDOP) + float get_positional_dilution_of_precision() const; + + /// @brief Sets the positional dilution of precision (PDOP) + /// @param[in] pdop The positional dilution of precision to set + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_positional_dilution_of_precision(std::int16_t pdop); + + /// @brief Returns the number of reference stations used in this position solution (if applicable to GNSS method) + /// @returns The number of reference stations used in this position solution + std::uint8_t get_number_of_reference_stations() const; + + /// @brief Sets the number of reference stations used in this position solution + /// @param[in] stations The number of reference stations to set (if applicable to GNSS method, otherwise should be zero) + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_number_of_reference_stations(std::uint8_t stations); + + /// @brief Returns the specified reference station's ID by index + /// @param[in] index The index of the reference station to get the ID of + /// @returns Reference station's ID by index + std::uint16_t get_reference_station_id(std::size_t index) const; + + /// @brief Returns the specified reference station's DGNSS corrections age by index + /// @param[in] index The index of the reference station to get the DGNSS corrections age for + /// @returns Reference station's DGNSS corrections age by index + std::uint16_t get_raw_reference_station_corrections_age(std::size_t index) const; + + /// @brief Returns the specified reference station's DGNSS corrections age by index + /// @param[in] index The index of the reference station to get the DGNSS corrections age for + /// @returns Reference station's DGNSS corrections age by index + float get_reference_station_corrections_age(std::size_t index) const; + + /// @brief Returns the specified reference station's system type by index + /// @param[in] index The index of the reference station to get the system type for + /// @returns The specified reference station's system type by index + TypeOfSystem get_reference_station_system_type(std::size_t index) const; + + /// @brief Sets the data for the specified reference station by index + /// @param[in] index The index of the reference station to set + /// @param[in] ID The station ID to set + /// @param[in] type The type of reference station + /// @param[in] ageOfCorrections Age of the DGNSS corrections in units of 0.01 seconds + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_reference_station(std::size_t index, std::uint16_t ID, TypeOfSystem type, std::uint16_t ageOfCorrections); + + /// @brief Returns the date associated with the current position. + /// @returns Number of days relative to UTC since Jan 1 1970 (0 is equal to Jan 1, 1970). Max value is 65532 days. + std::uint16_t get_position_date() const; + + /// @brief Sets the date to report relative to UTC since Jan 1 1970. Max normal value is 65532 + /// @param[in] dateToSet Date to report relative to UTC since Jan 1 1970. Max normal value is 65532 + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_position_date(std::uint16_t dateToSet); + + /// @brief Returns the number of seconds since midnight + /// @returns Number of seconds since midnight (0 == midnight), range allows for up to two leap seconds per day + std::uint32_t get_raw_position_time() const; + + /// @brief Returns the number of seconds since midnight + /// @returns Number of seconds since midnight (0 == midnight), range allows for up to two leap seconds per day, in units of 0.0001 seconds + double get_position_time() const; + + /// @brief Sets the number of seconds since midnight + /// @param[in] timeToSet Seconds since midnight (0 == midnight), range allows for up to two leap seconds per day, in units of 0.0001 seconds + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_position_time(std::uint32_t timeToSet); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + /// @brief Used to group related reference station data together + class ReferenceStationData + { + public: + /// @brief Default constructor for a ReferenceStationData with default values + ReferenceStationData() = default; + + /// @brief Constructor for ReferenceStationData that initializes all values to provided values + /// @param[in] id The station ID to set + /// @param[in] type The station system type to set + /// @param[in] age The age of DGNSS corrections to set + ReferenceStationData(std::uint16_t id, TypeOfSystem type, std::uint16_t age); + std::uint16_t stationID = 0; ///< The station ID of this reference. Can sometimes be used to infer your correction source. + TypeOfSystem stationType = TypeOfSystem::Null; ///< The type of reference station + std::uint16_t ageOfDGNSSCorrections = 0xFFFF; ///< Stores the age of the corrections from this reference + }; + + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 1000; ///< The transmit interval for this message as specified in NMEA2000 + static constexpr std::uint8_t MINIMUM_LENGTH_BYTES = 43; ///< The minimum size of this message in bytes + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::vector referenceStations; ///< Stores data about the reference stations used to generate this position solution. + std::int64_t altitude = 0; ///< The current altitude in 1x10E-6 meters. Range is +/- 9.223 x 10E+12 meters + std::int64_t latitude = 0; ///< The current latitude in 1x10E-16 degrees. Range is -90 to 90 degrees. Negative values are south latitudes. + std::int64_t longitude = 0; ///< The current longitude in 1x10E-16 degrees. Range is -90 to 90 degrees. Negative values are west longitudes. + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + std::uint32_t positionTime = 0; ///< The number of seconds since midnight on the current day. Allows for up to 2 leap seconds per day. Max value is 86401 seconds. + std::int32_t geoidalSeparation = 0; ///< The difference between the earth ellipsoid and mean-sea-level (geoid) defined by the reference datum used in the position solution. + std::uint16_t positionDate = 0; ///< Number of days relative to UTC since Jan 1 1970 (so 0 is equal to Jan 1, 1970). Max value is 65532 days. + std::int16_t horizontalDilutionOfPrecision = 0; ///< Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + std::int16_t positionalDilutionOfPrecision = 0; ///< Indicates the contribution of satellite configuration geometry to positioning error. Lower is better. + std::uint8_t numberOfSpaceVehicles = 0; ///< Number of GPS satellites in view. + std::uint8_t sequenceID = 0; ///< The sequence identifier field is used to tie related PGNs together. Somewhat arbitrary. + TypeOfSystem systemType = TypeOfSystem::Null; ///< The type of GNSS system used when generating this message + GNSSMethod method = GNSSMethod::NoGNSS; ///< Stores the method used to provide the GNSS fix + Integrity integrityChecking = Integrity::NoIntegrityChecking; ///< Stores the integrity of the values in the message + }; + + /// @brief A NMEA2000 message that describes datum (reference frame) information. PGN 129044 (0x1F814) + /// A common one might be the WGS84 datum or the NSRS, for example. + /// @details This provides local geodetic datum and datum offsets from a reference datum. + /// This PGN is used to define the datum to which a position location output by the same device in other PGNs is referenced. + class Datum + { + public: + /// @brief Constructor for a Datum message data object + /// @param[in] source The control function sending the message + explicit Datum(std::shared_ptr source); + + /// @brief Returns the control function sending this instance of this message + /// @returns The control function sending this instance of this message + std::shared_ptr get_control_function() const; + + /// @brief Returns the 4 character ascii datum code + /// @returns The 4 character ascii datum code + std::string get_local_datum() const; + + /// @brief Sets the local datum's 4 character ascii datum code + /// @param[in] datum The datum code to set + /// @returns True if the value that was set differed from the stored value + bool set_local_datum(const std::string &datum); + + /// @brief Returns the 4 character ascii datum code that identifies the reference datum + /// @returns The 4 character ascii datum code that identifies the reference datum + std::string get_reference_datum() const; + + /// @brief Sets the 4 character ascii datum code that identifies the reference datum + /// @param[in] datum The datum code to set, must be 4 characters + /// @returns True if the value that was set differed from the stored value + bool set_reference_datum(const std::string &datum); + + /// @brief Returns latitude offset of position in the local datum from the position in the reference datum. In units of 1x10E-7 degrees + /// @returns Latitude offset of position in the local datum from the position in the reference datum. In units of 1x10E-7 degrees + std::int32_t get_raw_delta_latitude() const; + + /// @brief Returns latitude offset of position in the local datum from the position in the reference datum. In units of degrees + /// @returns Latitude offset of position in the local datum from the position in the reference datum. In units of degrees + double get_delta_latitude() const; + + /// @brief Sets latitude offset of position in the local datum from the position in the reference datum in units of 1x10E-7 degrees. + /// @param[in] delta The latitude offset to set in units of 1x10E-7 degrees + /// @returns True if the value that was set differed from the stored value + bool set_delta_latitude(std::int32_t delta); + + /// @brief Returns longitude offset of position in the local datum from the position in the reference datum. In units of 1x10E-7 degrees + /// @returns Longitude offset of position in the local datum from the position in the reference datum. In units of 1x10E-7 degrees + std::int32_t get_raw_delta_longitude() const; + + /// @brief Returns longitude offset of position in the local datum from the position in the reference datum. In units of degrees + /// @returns Longitude offset of position in the local datum from the position in the reference datum. In units of degrees + double get_delta_longitude() const; + + /// @brief Sets longitude offset of position in the local datum from the position in the reference datum in units of 1x10E-7 degrees. + /// @param[in] delta The longitude offset to set in units of 1x10E-7 degrees + /// @returns True if the value that was set differed from the stored value + bool set_delta_longitude(std::int32_t delta); + + /// @brief Returns the altitude offset of position in the local datum relative to the position in the reference datum in units of The altitude delta in units of 0.01 meters. + /// @returns The altitude offset of position in the local datum relative to the position in the reference datum in units of The altitude delta in units of 0.01 meters. + std::int32_t get_raw_delta_altitude() const; + + /// @brief Returns the altitude offset of position in the local datum relative to the position in the reference datum in units of The altitude delta in units of meters. + /// @returns The altitude offset of position in the local datum relative to the position in the reference datum in units of The altitude delta in units of meters. + float get_delta_altitude() const; + + /// @brief Sets the altitude offset of position in the local datum relative to the position in the reference datum in units of The altitude delta in units of 0.01 meters. + /// @param[in] delta The altitude delta to set in units of 0.01 meters + /// @returns True if the value that was set differed from the stored value + bool set_delta_altitude(std::int32_t delta); + + /// @brief Returns a timestamp in milliseconds corresponding to when the message was last sent or received + /// @returns A timestamp in milliseconds corresponding to when the message was last sent or received + std::uint32_t get_timestamp() const; + + /// @brief Sets the time in milliseconds when the message was last sent or received + /// @param[in] timestamp The timestamp (in milliseconds) to set for when this message was sent or received + /// @returns True if the value that was set differed from the stored value, otherwise false + bool set_timestamp(std::uint32_t timestamp); + + /// @brief Serializes the current state of this object into a buffer to be sent on the CAN bus + /// @param[in] buffer A buffer to serialize the message data into + void serialize(std::vector &buffer) const; + + /// @brief Deserializes a CAN message to populate this object's contents. Updates the timestamp when called. + /// @param[in] receivedMessage The CAN message to parse when deserializing + /// @returns True if the message was successfully deserialized and the data content was different than the stored content. + bool deserialize(const CANMessage &receivedMessage); + + /// @brief Returns the timeout (the sending interval) for this message in milliseconds + /// @returns This message's timeout (the sending interval) in milliseconds + static std::uint32_t get_timeout(); + + private: + static constexpr std::uint32_t CYCLIC_MESSAGE_RATE_MS = 10000; ///< The transmit interval for this message as specified in NMEA2000 + static constexpr std::uint8_t LENGTH_BYTES = 20; ///< The size of this message in bytes + static constexpr std::uint8_t DATUM_STRING_LENGTHS = 4; ///< The size of the datum codes in bytes + + std::shared_ptr senderControlFunction; ///< The sender of the message data + std::string localDatum; ///< A 4 character ascii datum code. The first three chars are the datum ID.The fourth char is the local datum subdivision code or a null character if it is unknown or unused. + std::string referenceDatum; ///< A 4 character ascii datum code that identifies the reference datum. + std::int32_t deltaLatitude = 0; ///< Position in the local datum is offset from the position in the reference datum as indicated by this latitude delta. In units of 1x10E-7 degrees. + std::int32_t deltaLongitude = 0; ///< Position in the local datum is offset from the position in the reference datum as indicated by this longitude delta. In units of 1x10E-7 degrees. + std::int32_t deltaAltitude = 0; ///< The altitude delta in units of 0.01 meters. Positive values indicate Up. + std::uint32_t messageTimestamp_ms = 0; ///< A timestamp in milliseconds when this message was last sent or received + }; + } // namespace NMEA2000Messages +} // namespace isobus +#endif // NMEA2000_MESSAGE_DEFINITIONS_HPP diff --git a/src/nmea2000_message_interface.cpp b/src/nmea2000_message_interface.cpp new file mode 100644 index 0000000..b5b7f24 --- /dev/null +++ b/src/nmea2000_message_interface.cpp @@ -0,0 +1,788 @@ +//================================================================================================ +/// @file nmea2000_message_interface.cpp +/// +/// @brief Implements a message interface for processing or sending NMEA2K messages commonly used +/// on an ISO 11783 network. +/// +/// @details This interface provides a common interface for sending and receiving common +/// NMEA2000 messages that might be found on an ISO 11783 network. ISO11783-7 defines +/// that GNSS information be sent using NMEA2000 parameter groups like the ones included +/// in this interface. +/// +/// @note This library and its authors are not affiliated with the National Marine +/// Electronics Association in any way. +/// +/// @author Adrian Del Grosso +/// +/// @copyright 2023 Adrian Del Grosso +//================================================================================================ +#include "nmea2000_message_interface.hpp" +#include "can_general_parameter_group_numbers.hpp" +#include "can_network_manager.hpp" +#include "can_stack_logger.hpp" +#include "nmea2000_fast_packet_protocol.hpp" +#include "system_timing.hpp" + +#include + +namespace isobus +{ + using namespace NMEA2000Messages; + + NMEA2000MessageInterface::NMEA2000MessageInterface(std::shared_ptr sendingControlFunction, + bool enableSendingCogSogCyclically, + bool enableSendingDatumCyclically, + bool enableSendingGNSSPositionDataCyclically, + bool enableSendingPositionDeltaHighPrecisionRapidUpdateCyclically, + bool enableSendingPositionRapidUpdateCyclically, + bool enableSendingRateOfTurnCyclically, + bool enableSendingVesselHeadingCyclically) : + txFlags(static_cast(TransmitFlags::NumberOfFlags), process_flags, this), + cogSogTransmitMessage(sendingControlFunction), + datumTransmitMessage(sendingControlFunction), + gnssPositionDataTransmitMessage(sendingControlFunction), + positionDeltaHighPrecisionRapidUpdateTransmitMessage(sendingControlFunction), + positionRapidUpdateTransmitMessage(sendingControlFunction), + rateOfTurnTransmitMessage(sendingControlFunction), + vesselHeadingTransmitMessage(sendingControlFunction), + sendCogSogCyclically(enableSendingCogSogCyclically), + sendDatumCyclically(enableSendingDatumCyclically), + sendGNSSPositionDataCyclically(enableSendingGNSSPositionDataCyclically), + sendPositionDeltaHighPrecisionRapidUpdateCyclically(enableSendingPositionDeltaHighPrecisionRapidUpdateCyclically), + sendPositionRapidUpdateCyclically(enableSendingPositionRapidUpdateCyclically), + sendRateOfTurnCyclically(enableSendingRateOfTurnCyclically), + sendVesselHeadingCyclically(enableSendingVesselHeadingCyclically) + { + } + + NMEA2000MessageInterface::~NMEA2000MessageInterface() + { + terminate(); + } + + NMEA2000Messages::CourseOverGroundSpeedOverGroundRapidUpdate &NMEA2000MessageInterface::get_cog_sog_transmit_message() + { + return cogSogTransmitMessage; + } + + NMEA2000Messages::Datum &NMEA2000MessageInterface::get_datum_transmit_message() + { + return datumTransmitMessage; + } + + NMEA2000Messages::GNSSPositionData &NMEA2000MessageInterface::get_gnss_position_data_transmit_message() + { + return gnssPositionDataTransmitMessage; + } + + NMEA2000Messages::PositionDeltaHighPrecisionRapidUpdate &NMEA2000MessageInterface::get_position_delta_high_precision_rapid_update_transmit_message() + { + return positionDeltaHighPrecisionRapidUpdateTransmitMessage; + } + + NMEA2000Messages::PositionRapidUpdate &NMEA2000MessageInterface::get_position_rapid_update_transmit_message() + { + return positionRapidUpdateTransmitMessage; + } + + NMEA2000Messages::RateOfTurn &NMEA2000MessageInterface::get_rate_of_turn_transmit_message() + { + return rateOfTurnTransmitMessage; + } + + NMEA2000Messages::VesselHeading &NMEA2000MessageInterface::get_vessel_heading_transmit_message() + { + return vesselHeadingTransmitMessage; + } + + std::size_t NMEA2000MessageInterface::get_number_received_course_speed_over_ground_message_sources() const + { + return receivedCogSogMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_datum_message_sources() const + { + return receivedDatumMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_gnss_position_data_message_sources() const + { + return receivedGNSSPositionDataMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_position_delta_high_precision_rapid_update_message_sources() const + { + return receivedPositionDeltaHighPrecisionRapidUpdateMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_position_rapid_update_message_sources() const + { + return receivedPositionRapidUpdateMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_rate_of_turn_message_sources() const + { + return receivedRateOfTurnMessages.size(); + } + + std::size_t NMEA2000MessageInterface::get_number_received_vessel_heading_message_sources() const + { + return receivedVesselHeadingMessages.size(); + } + + std::shared_ptr NMEA2000MessageInterface::get_received_course_speed_over_ground_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedCogSogMessages.size()) + { + retVal = receivedCogSogMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_datum_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedDatumMessages.size()) + { + retVal = receivedDatumMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_gnss_position_data_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedGNSSPositionDataMessages.size()) + { + retVal = receivedGNSSPositionDataMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_position_delta_high_precision_rapid_update_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedPositionDeltaHighPrecisionRapidUpdateMessages.size()) + { + retVal = receivedPositionDeltaHighPrecisionRapidUpdateMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_position_rapid_update_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedPositionRapidUpdateMessages.size()) + { + retVal = receivedPositionRapidUpdateMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_rate_of_turn_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedRateOfTurnMessages.size()) + { + retVal = receivedRateOfTurnMessages.at(index); + } + return retVal; + } + + std::shared_ptr NMEA2000MessageInterface::get_received_vessel_heading_message(std::size_t index) const + { + std::shared_ptr retVal = nullptr; + + if (index < receivedVesselHeadingMessages.size()) + { + retVal = receivedVesselHeadingMessages.at(index); + } + return retVal; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_course_speed_over_ground_rapid_update_event_publisher() + { + return cogSogEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_datum_event_publisher() + { + return datumEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_gnss_position_data_event_publisher() + { + return gnssPositionDataEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_position_delta_high_precision_rapid_update_event_publisher() + { + return positionDeltaHighPrecisionRapidUpdateEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_position_rapid_update_event_publisher() + { + return positionRapidUpdateEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_rate_of_turn_event_publisher() + { + return rateOfTurnEventPublisher; + } + + EventDispatcher, bool> &NMEA2000MessageInterface::get_vessel_heading_event_publisher() + { + return vesselHeadingEventPublisher; + } + + bool NMEA2000MessageInterface::get_enable_sending_cog_sog_cyclically() const + { + return sendCogSogCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_cog_sog_cyclically(bool enable) + { + sendCogSogCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_datum_cyclically() const + { + return sendDatumCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_datum_cyclically(bool enable) + { + sendDatumCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_gnss_position_data_cyclically() const + { + return sendGNSSPositionDataCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_gnss_position_data_cyclically(bool enable) + { + sendGNSSPositionDataCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_position_delta_high_precision_rapid_update_cyclically() const + { + return sendPositionDeltaHighPrecisionRapidUpdateCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_position_delta_high_precision_rapid_update_cyclically(bool enable) + { + sendPositionDeltaHighPrecisionRapidUpdateCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_position_rapid_update_cyclically() const + { + return sendPositionRapidUpdateCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_position_rapid_update_cyclically(bool enable) + { + sendPositionRapidUpdateCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_rate_of_turn_cyclically() const + { + return sendRateOfTurnCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_rate_of_turn_cyclically(bool enable) + { + sendRateOfTurnCyclically = enable; + } + + bool NMEA2000MessageInterface::get_enable_sending_vessel_heading_cyclically() const + { + return sendVesselHeadingCyclically; + } + + void NMEA2000MessageInterface::set_enable_sending_vessel_heading_cyclically(bool enable) + { + sendVesselHeadingCyclically = enable; + } + + void NMEA2000MessageInterface::initialize() + { + if (!initialized) + { + CANNetworkManager::CANNetwork.get_fast_packet_protocol().register_multipacket_message_callback(static_cast(CANLibParameterGroupNumber::Datum), process_rx_message, this); + CANNetworkManager::CANNetwork.get_fast_packet_protocol().register_multipacket_message_callback(static_cast(CANLibParameterGroupNumber::GNSSPositionData), process_rx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::CourseOverGroundSpeedOverGroundRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::PositionDeltaHighPrecisionRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::PositionRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::RateOfTurn), process_rx_message, this); + CANNetworkManager::CANNetwork.add_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VesselHeading), process_rx_message, this); + initialized = true; + } + } + + bool NMEA2000MessageInterface::get_initialized() const + { + return initialized; + } + + void NMEA2000MessageInterface::terminate() + { + if (initialized) + { + CANNetworkManager::CANNetwork.get_fast_packet_protocol().remove_multipacket_message_callback(static_cast(CANLibParameterGroupNumber::Datum), process_rx_message, this); + CANNetworkManager::CANNetwork.get_fast_packet_protocol().remove_multipacket_message_callback(static_cast(CANLibParameterGroupNumber::GNSSPositionData), process_rx_message, this); + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::CourseOverGroundSpeedOverGroundRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::PositionDeltaHighPrecisionRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::PositionRapidUpdate), process_rx_message, this); + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::RateOfTurn), process_rx_message, this); + CANNetworkManager::CANNetwork.remove_any_control_function_parameter_group_number_callback(static_cast(CANLibParameterGroupNumber::VesselHeading), process_rx_message, this); + initialized = false; + } + } + + void NMEA2000MessageInterface::update() + { + if (initialized) + { + check_transmit_timeouts(); + txFlags.process_all_flags(); + check_receive_timeouts(); + } + else + { + CANStackLogger::error("[NMEA2K]: Interface not initialized!"); + } + } + + void NMEA2000MessageInterface::process_flags(std::uint32_t flag, void *parentPointer) + { + if ((nullptr != parentPointer) && + (flag < static_cast(TransmitFlags::NumberOfFlags))) + { + auto targetInterface = static_cast(parentPointer); + std::vector messageBuffer; + bool transmitSuccessful = true; + + switch (static_cast(flag)) + { + case TransmitFlags::CourseOverGroundSpeedOverGroundRapidUpdate: + { + if (nullptr != targetInterface->cogSogTransmitMessage.get_control_function()) + { + targetInterface->cogSogTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::CourseOverGroundSpeedOverGroundRapidUpdate), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->cogSogTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority2); + } + } + break; + + case TransmitFlags::Datum: + { + if (nullptr != targetInterface->datumTransmitMessage.get_control_function()) + { + targetInterface->datumTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.get_fast_packet_protocol().send_multipacket_message(static_cast(CANLibParameterGroupNumber::Datum), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->datumTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::PriorityDefault6); + } + } + break; + + case TransmitFlags::GNSSPositionData: + { + if (nullptr != targetInterface->gnssPositionDataTransmitMessage.get_control_function()) + { + targetInterface->gnssPositionDataTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.get_fast_packet_protocol().send_multipacket_message(static_cast(CANLibParameterGroupNumber::GNSSPositionData), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->gnssPositionDataTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority3); + } + } + break; + + case TransmitFlags::PositionDeltaHighPrecisionRapidUpdate: + { + if (nullptr != targetInterface->positionDeltaHighPrecisionRapidUpdateTransmitMessage.get_control_function()) + { + targetInterface->positionDeltaHighPrecisionRapidUpdateTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::PositionDeltaHighPrecisionRapidUpdate), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->positionDeltaHighPrecisionRapidUpdateTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority2); + } + } + break; + + case TransmitFlags::PositionRapidUpdate: + { + if (nullptr != targetInterface->positionRapidUpdateTransmitMessage.get_control_function()) + { + targetInterface->positionRapidUpdateTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::PositionRapidUpdate), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->positionRapidUpdateTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority2); + } + } + break; + + case TransmitFlags::RateOfTurn: + { + if (nullptr != targetInterface->rateOfTurnTransmitMessage.get_control_function()) + { + targetInterface->rateOfTurnTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::RateOfTurn), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->rateOfTurnTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority2); + } + } + break; + + case TransmitFlags::VesselHeading: + { + if (nullptr != targetInterface->vesselHeadingTransmitMessage.get_control_function()) + { + targetInterface->vesselHeadingTransmitMessage.serialize(messageBuffer); + transmitSuccessful = CANNetworkManager::CANNetwork.send_can_message(static_cast(CANLibParameterGroupNumber::VesselHeading), + messageBuffer.data(), + messageBuffer.size(), + std::static_pointer_cast(targetInterface->vesselHeadingTransmitMessage.get_control_function()), + nullptr, + CANIdentifier::CANPriority::Priority2); + } + } + break; + + default: + break; + } + + if (!transmitSuccessful) + { + targetInterface->txFlags.set_flag(static_cast(flag)); + } + } + } + + void NMEA2000MessageInterface::process_rx_message(const CANMessage &message, void *parentPointer) + { + if (nullptr != parentPointer) + { + auto targetInterface = static_cast(parentPointer); + + switch (message.get_identifier().get_parameter_group_number()) + { + case static_cast(CANLibParameterGroupNumber::CourseOverGroundSpeedOverGroundRapidUpdate): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedCogSogMessages.begin(), + targetInterface->receivedCogSogMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedCogSogMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedCogSogMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedCogSogMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->cogSogEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::Datum): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedDatumMessages.begin(), + targetInterface->receivedDatumMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedDatumMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedDatumMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedDatumMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->datumEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::GNSSPositionData): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedGNSSPositionDataMessages.begin(), + targetInterface->receivedGNSSPositionDataMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedGNSSPositionDataMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedGNSSPositionDataMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedGNSSPositionDataMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->gnssPositionDataEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::PositionDeltaHighPrecisionRapidUpdate): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedPositionDeltaHighPrecisionRapidUpdateMessages.begin(), + targetInterface->receivedPositionDeltaHighPrecisionRapidUpdateMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedPositionDeltaHighPrecisionRapidUpdateMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedPositionDeltaHighPrecisionRapidUpdateMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedPositionDeltaHighPrecisionRapidUpdateMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->positionDeltaHighPrecisionRapidUpdateEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::PositionRapidUpdate): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedPositionRapidUpdateMessages.begin(), + targetInterface->receivedPositionRapidUpdateMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedPositionRapidUpdateMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedPositionRapidUpdateMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedPositionRapidUpdateMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->positionRapidUpdateEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::RateOfTurn): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedRateOfTurnMessages.begin(), + targetInterface->receivedRateOfTurnMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedRateOfTurnMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedRateOfTurnMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedRateOfTurnMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->rateOfTurnEventPublisher.call(*result, anySignalChanged); + } + } + break; + + case static_cast(CANLibParameterGroupNumber::VesselHeading): + { + if (message.get_source_control_function() != nullptr) + { + auto result = std::find_if(targetInterface->receivedVesselHeadingMessages.begin(), + targetInterface->receivedVesselHeadingMessages.end(), + [&message](const std::shared_ptr &receivedCommand) { + return (nullptr != receivedCommand) && (receivedCommand->get_control_function() == message.get_source_control_function()); + }); + + if (result == targetInterface->receivedVesselHeadingMessages.end()) + { + // There is no existing message object from this control function, so create a new one + targetInterface->receivedVesselHeadingMessages.push_back(std::make_shared(message.get_source_control_function())); + result = targetInterface->receivedVesselHeadingMessages.end() - 1; + } + + bool anySignalChanged = (*result)->deserialize(message); + targetInterface->vesselHeadingEventPublisher.call(*result, anySignalChanged); + } + } + break; + + default: + break; + } + } + } + + void NMEA2000MessageInterface::check_receive_timeouts() + { + if (initialized) + { + receivedCogSogMessages.erase(std::remove_if(receivedCogSogMessages.begin(), + receivedCogSogMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * CourseOverGroundSpeedOverGroundRapidUpdate::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: COG & SOG message Rx timeout."); + return true; + } + return false; + }), + receivedCogSogMessages.end()); + receivedDatumMessages.erase(std::remove_if(receivedDatumMessages.begin(), + receivedDatumMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * Datum::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: Datum message Rx timeout."); + return true; + } + return false; + }), + receivedDatumMessages.end()); + receivedGNSSPositionDataMessages.erase(std::remove_if(receivedGNSSPositionDataMessages.begin(), + receivedGNSSPositionDataMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * GNSSPositionData::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: GNSS position data message Rx timeout."); + return true; + } + return false; + }), + receivedGNSSPositionDataMessages.end()); + receivedPositionDeltaHighPrecisionRapidUpdateMessages.erase(std::remove_if(receivedPositionDeltaHighPrecisionRapidUpdateMessages.begin(), + receivedPositionDeltaHighPrecisionRapidUpdateMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * PositionDeltaHighPrecisionRapidUpdate::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: Position Delta High Precision Rapid Update Rx timeout."); + return true; + } + return false; + }), + receivedPositionDeltaHighPrecisionRapidUpdateMessages.end()); + receivedPositionRapidUpdateMessages.erase(std::remove_if(receivedPositionRapidUpdateMessages.begin(), + receivedPositionRapidUpdateMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * PositionRapidUpdate::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: Position delta high precision rapid update message Rx timeout."); + return true; + } + return false; + }), + receivedPositionRapidUpdateMessages.end()); + receivedRateOfTurnMessages.erase(std::remove_if(receivedRateOfTurnMessages.begin(), + receivedRateOfTurnMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * RateOfTurn::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: Rate of turn message Rx timeout."); + return true; + } + return false; + }), + receivedRateOfTurnMessages.end()); + receivedVesselHeadingMessages.erase(std::remove_if(receivedVesselHeadingMessages.begin(), + receivedVesselHeadingMessages.end(), + [](std::shared_ptr message) { + if (SystemTiming::time_expired_ms(message->get_timestamp(), 3 * VesselHeading::get_timeout())) + { + CANStackLogger::warn("[NMEA2K]: Vessel heading message Rx timeout."); + return true; + } + return false; + }), + receivedVesselHeadingMessages.end()); + } + } + + void NMEA2000MessageInterface::check_transmit_timeouts() + { + if (sendCogSogCyclically && SystemTiming::time_expired_ms(cogSogTransmitMessage.get_timestamp(), CourseOverGroundSpeedOverGroundRapidUpdate::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::CourseOverGroundSpeedOverGroundRapidUpdate)); + cogSogTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendDatumCyclically && SystemTiming::time_expired_ms(datumTransmitMessage.get_timestamp(), Datum::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::Datum)); + datumTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendPositionDeltaHighPrecisionRapidUpdateCyclically && SystemTiming::time_expired_ms(positionDeltaHighPrecisionRapidUpdateTransmitMessage.get_timestamp(), PositionDeltaHighPrecisionRapidUpdate::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::PositionDeltaHighPrecisionRapidUpdate)); + positionDeltaHighPrecisionRapidUpdateTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendGNSSPositionDataCyclically && SystemTiming::time_expired_ms(gnssPositionDataTransmitMessage.get_timestamp(), GNSSPositionData::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::GNSSPositionData)); + gnssPositionDataTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendPositionRapidUpdateCyclically && SystemTiming::time_expired_ms(positionRapidUpdateTransmitMessage.get_timestamp(), PositionRapidUpdate::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::PositionRapidUpdate)); + positionRapidUpdateTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendRateOfTurnCyclically && SystemTiming::time_expired_ms(rateOfTurnTransmitMessage.get_timestamp(), RateOfTurn::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::RateOfTurn)); + rateOfTurnTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + if (sendVesselHeadingCyclically && SystemTiming::time_expired_ms(vesselHeadingTransmitMessage.get_timestamp(), VesselHeading::get_timeout())) + { + txFlags.set_flag(static_cast(TransmitFlags::VesselHeading)); + vesselHeadingTransmitMessage.set_timestamp(SystemTiming::get_timestamp_ms()); + } + } +} // namespace isobus diff --git a/src/nmea2000_message_interface.hpp b/src/nmea2000_message_interface.hpp new file mode 100644 index 0000000..75b0a21 --- /dev/null +++ b/src/nmea2000_message_interface.hpp @@ -0,0 +1,339 @@ +//================================================================================================ +/// @file nmea2000_message_interface.hpp +/// +/// @brief A message interface for processing or sending NMEA2K messages commonly used on +/// an ISO 11783 network. +/// +/// @details This interface provides a common interface for sending and receiving common +/// NMEA2000 messages that might be found on an ISO 11783 network. ISO11783-7 defines +/// that GNSS information be sent using NMEA2000 parameter groups like the ones included +/// in this interface. +/// +/// @note This library and its authors are not affiliated with the National Marine +/// Electronics Association in any way. +/// +/// @author Adrian Del Grosso +/// +/// @copyright 2023 Adrian Del Grosso +//================================================================================================ +#ifndef NMEA2000_MESSAGE_INTERFACE_HPP +#define NMEA2000_MESSAGE_INTERFACE_HPP + +#include "nmea2000_message_definitions.hpp" +#include "event_dispatcher.hpp" +#include "processing_flags.hpp" + +namespace isobus +{ + /// @brief An interface for sending and receiving common NMEA2000 messages on an ISO11783 network + class NMEA2000MessageInterface + { + public: + /// @brief Constructor for a NMEA2000MessageInterface + /// @param[in] sendingControlFunction The control function the interface should use to send messages, or nullptr optionally + /// @param[in] enableSendingCogSogCyclically Set to true for the interface to attempt to send the COG & SOG message cyclically + /// @param[in] enableSendingDatumCyclically Set to true for the interface to attempt to send the Datum message cyclically + /// @param[in] enableSendingGNSSPositionDataCyclically Set to true for the interface to attempt to send the GNSS position data message message cyclically + /// @param[in] enableSendingPositionDeltaHighPrecisionRapidUpdateCyclically Set to true for the interface to attempt to send the position delta message cyclically + /// @param[in] enableSendingPositionRapidUpdateCyclically Set to true for the interface to attempt to send the position rapid update message cyclically + /// @param[in] enableSendingRateOfTurnCyclically Set to true for the interface to attempt to send the rate of turn message cyclically + /// @param[in] enableSendingVesselHeadingCyclically Set to true for the interface to attempt to send the vessel heading message cyclically + NMEA2000MessageInterface(std::shared_ptr sendingControlFunction, + bool enableSendingCogSogCyclically, + bool enableSendingDatumCyclically, + bool enableSendingGNSSPositionDataCyclically, + bool enableSendingPositionDeltaHighPrecisionRapidUpdateCyclically, + bool enableSendingPositionRapidUpdateCyclically, + bool enableSendingRateOfTurnCyclically, + bool enableSendingVesselHeadingCyclically); + + /// @brief Destructor for a NMEA2000MessageInterface + ~NMEA2000MessageInterface(); + + /// @brief Returns a CourseOverGroundSpeedOverGroundRapidUpdate object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns CourseOverGroundSpeedOverGroundRapidUpdate used to set the individual signal values sent in the COG & SOG message + NMEA2000Messages::CourseOverGroundSpeedOverGroundRapidUpdate &get_cog_sog_transmit_message(); + + /// @brief Returns a Datum object that you can use to set the message's individual signal values, + /// which will then be transmitted if the interface is configured to do so. + /// @returns Datum used to set the individual signal values sent in the Datum message + NMEA2000Messages::Datum &get_datum_transmit_message(); + + /// @brief Returns a GNSSPositionData object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns GNSSPositionData used to set the individual signal values sent in the GNSS position data message + NMEA2000Messages::GNSSPositionData &get_gnss_position_data_transmit_message(); + + /// @brief Returns a PositionDeltaHighPrecisionRapidUpdate object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns PositionDeltaHighPrecisionRapidUpdate used to set the individual signal values sent in the position delta message + NMEA2000Messages::PositionDeltaHighPrecisionRapidUpdate &get_position_delta_high_precision_rapid_update_transmit_message(); + + /// @brief Returns a PositionRapidUpdate object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns PositionRapidUpdate used to set the individual signal values sent in the position rapid update message + NMEA2000Messages::PositionRapidUpdate &get_position_rapid_update_transmit_message(); + + /// @brief Returns a RateOfTurn object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns RateOfTurn used to set the individual signal values sent in the rate of turn message + NMEA2000Messages::RateOfTurn &get_rate_of_turn_transmit_message(); + + /// @brief Returns a VesselHeading object that you can use to + /// set the message's individual signal values, which will then be transmitted if the interface is configured to do so. + /// @returns VesselHeading used to set the individual signal values sent in the vessel heading message + NMEA2000Messages::VesselHeading &get_vessel_heading_transmit_message(); + + /// @brief Returns the number of unique senders of the COG & SOG message + /// @returns The number of unique COG & SOG message senders + std::size_t get_number_received_course_speed_over_ground_message_sources() const; + + /// @brief Returns the number of unique datum message senders + /// @returns The number of unique datum message senders + std::size_t get_number_received_datum_message_sources() const; + + /// @brief Returns the number of unique GNSS position data message senders + /// @returns The number of GNSS position data message senders + std::size_t get_number_received_gnss_position_data_message_sources() const; + + /// @brief Returns the number of unique delta position message senders + /// @returns The number of unique position delta high precision rapid update message senders + std::size_t get_number_received_position_delta_high_precision_rapid_update_message_sources() const; + + /// @brief Returns the number of unique position rapid update message senders + /// @returns The number of unique position rapid update message senders + std::size_t get_number_received_position_rapid_update_message_sources() const; + + /// @brief Returns the number of unique rate of turn message senders + /// @returns The number of unique rate of turn message senders + std::size_t get_number_received_rate_of_turn_message_sources() const; + + /// @brief Returns the number of unique vessel heading message senders + /// @returns The number of unique vessel heading message senders + std::size_t get_number_received_vessel_heading_message_sources() const; + + /// @brief Returns the content of the COG & SOG message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the COG & SOG message + std::shared_ptr get_received_course_speed_over_ground_message(std::size_t index) const; + + /// @brief Returns the content of the Datum message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the Datum message + std::shared_ptr get_received_datum_message(std::size_t index) const; + + /// @brief Returns the content of the GNSS position data message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the GNSS position data message + std::shared_ptr get_received_gnss_position_data_message(std::size_t index) const; + + /// @brief Returns the content of the position delta high precision rapid update message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the position delta high precision rapid update message + std::shared_ptr get_received_position_delta_high_precision_rapid_update_message(std::size_t index) const; + + /// @brief Returns the content of the position rapid update message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the position rapid update message + std::shared_ptr get_received_position_rapid_update_message(std::size_t index) const; + + /// @brief Returns the content of the rate of turn message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the rate of turn message + std::shared_ptr get_received_rate_of_turn_message(std::size_t index) const; + + /// @brief Returns the content of the vessel heading message + /// based on the index of the sender. Use this to read the received messages' content. + /// @param[in] index An index of senders of the the message + /// @note Only one device on the bus will send this normally, but we provide a generic way to get + /// an arbitrary number of these. So generally using only index 0 will be acceptable. + /// @note It is also possible that this message may not be present, depending on your machine. + /// @returns The content of the vessel heading message + std::shared_ptr get_received_vessel_heading_message(std::size_t index) const; + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated COG & SOG messages are received. + /// @returns The event publisher for COG & SOG messages + EventDispatcher, bool> &get_course_speed_over_ground_rapid_update_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated datum messages are received. + /// @returns The event publisher for datum messages + EventDispatcher, bool> &get_datum_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated GNSS position data messages are received. + /// @returns The event publisher for GNSS position data messages + EventDispatcher, bool> &get_gnss_position_data_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated position delta high precision rapid update messages are received. + /// @returns The event publisher for position delta high precision rapid update messages + EventDispatcher, bool> &get_position_delta_high_precision_rapid_update_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated position rapid update messages are received. + /// @returns The event publisher for position rapid update messages + EventDispatcher, bool> &get_position_rapid_update_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated rate of turn messages are received. + /// @returns The event publisher for rate of turn messages + EventDispatcher, bool> &get_rate_of_turn_event_publisher(); + + /// @brief Returns an event dispatcher which you can use to get callbacks when new/updated vessel heading messages are received. + /// @returns The event publisher for vessel heading messages + EventDispatcher, bool> &get_vessel_heading_event_publisher(); + + /// @brief Returns if the interface has cyclic sending of the course/speed over ground message enabled + /// @returns True if the interface has cyclic sending of the course/speed over ground message enabled, otherwise false + bool get_enable_sending_cog_sog_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the course/speed over ground message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the course/speed over ground message cyclically + void set_enable_sending_cog_sog_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the datum message enabled + /// @returns True if the interface has cyclic sending of the datum message enabled, otherwise false + bool get_enable_sending_datum_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the datum data message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the datum message cyclically + void set_enable_sending_datum_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the GNSS position data message enabled + /// @returns True if the interface has cyclic sending of the GNSS position data message enabled, otherwise false + bool get_enable_sending_gnss_position_data_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the GNSS position data message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the GNSS position data message cyclically + void set_enable_sending_gnss_position_data_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the position delta high precision rapid update message enabled + /// @returns True if the interface has cyclic sending of the position delta high precision rapid update message enabled, otherwise false + bool get_enable_sending_position_delta_high_precision_rapid_update_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the position delta high precision rapid update message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the position delta high precision rapid update message cyclically + void set_enable_sending_position_delta_high_precision_rapid_update_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the position rapid update message enabled + /// @returns True if the interface has cyclic sending of the position rapid update message enabled, otherwise false + bool get_enable_sending_position_rapid_update_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the position rapid update message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the position rapid update message cyclically + void set_enable_sending_position_rapid_update_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the rate of turn message enabled + /// @returns True if the interface has cyclic sending of the rate of turn message enabled, otherwise false + bool get_enable_sending_rate_of_turn_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the rate of turn message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the rate of turn message cyclically + void set_enable_sending_rate_of_turn_cyclically(bool enable); + + /// @brief Returns if the interface has cyclic sending of the vessel heading message enabled + /// @returns True if the interface has cyclic sending of the vessel heading message enabled, otherwise false + bool get_enable_sending_vessel_heading_cyclically() const; + + /// @brief Instructs the interface to enable or disable sending the vessel heading message cyclically + /// @param[in] enable Set to true to have the interface cyclically send the vessel heading message cyclically + void set_enable_sending_vessel_heading_cyclically(bool enable); + + /// @brief Initializes the interface. Registers it with the network manager. Must be called before the interface can work properly. + void initialize(); + + /// @brief Returns if initialize has been called + /// @returns True if initialize has been called, otherwise false. Terminate sets this back to false. + bool get_initialized() const; + + /// @brief Unregisters the interface from the network manager + void terminate(); + + /// @brief Updates the diagnostic protocol. Must be called periodically. 50ms Is a good minimum interval for this object. + void update(); + + private: + /// @brief Enumerates a set of flags to manage sending various NMEA2000 messages from this interface + enum class TransmitFlags : std::uint32_t + { + CourseOverGroundSpeedOverGroundRapidUpdate = 0, + Datum, + GNSSPositionData, + PositionDeltaHighPrecisionRapidUpdate, + PositionRapidUpdate, + RateOfTurn, + VesselHeading, + + NumberOfFlags + }; + + /// @brief A generic callback for a the class to process flags from the `ProcessingFlags` + /// @param[in] flag The flag to process + /// @param[in] parentPointer A generic context pointer to reference a specific instance of this protocol in the callback + static void process_flags(std::uint32_t flag, void *parentPointer); + + /// @brief Processes a CAN message destined for an instance of this interface + /// @param[in] message The CAN message being received + /// @param[in] parentPointer A context variable to find the relevant class instance + static void process_rx_message(const CANMessage &message, void *parentPointer); + + /// @brief Checks to see if any received messages are timed out and prunes them if needed + void check_receive_timeouts(); + + /// @brief Checks to see if any transmit flags need to be set based on the last time the message was sent, if enabled. + void check_transmit_timeouts(); + + ProcessingFlags txFlags; ///< A set of flags used to track what messages need to be transmitted or retried + NMEA2000Messages::CourseOverGroundSpeedOverGroundRapidUpdate cogSogTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 129026 (0x1F802) if enabled + NMEA2000Messages::Datum datumTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 129044 (0x1F814) if enabled + NMEA2000Messages::GNSSPositionData gnssPositionDataTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 129029 (0x1F805) if enabled + NMEA2000Messages::PositionDeltaHighPrecisionRapidUpdate positionDeltaHighPrecisionRapidUpdateTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 129027 (0x1F803) if enabled + NMEA2000Messages::PositionRapidUpdate positionRapidUpdateTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 129025 (0x1F801) if enabled + NMEA2000Messages::RateOfTurn rateOfTurnTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 127251 (0x1F113) if enabled + NMEA2000Messages::VesselHeading vesselHeadingTransmitMessage; ///< Stores a set of data specifically for transmitting the PGN 127250 (0x1F112) if enabled + std::vector> receivedCogSogMessages; ///< Stores all received (and not timed out) sources of the COG & SOG message + std::vector> receivedDatumMessages; ///< Stores all received (and not timed out) sources of the Datum message + std::vector> receivedGNSSPositionDataMessages; ///< Stores all received (and not timed out) sources of the GNSS position data message + std::vector> receivedPositionDeltaHighPrecisionRapidUpdateMessages; ///< Stores all received (and not timed out) sources of the position delta message + std::vector> receivedPositionRapidUpdateMessages; ///< Stores all received (and not timed out) sources of the position rapid update message + std::vector> receivedRateOfTurnMessages; ///< Stores all received (and not timed out) sources of the rate of turn message + std::vector> receivedVesselHeadingMessages; ///< Stores all received (and not timed out) sources of the vessel heading message + EventDispatcher, bool> cogSogEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> datumEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> gnssPositionDataEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> positionDeltaHighPrecisionRapidUpdateEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> positionRapidUpdateEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> rateOfTurnEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + EventDispatcher, bool> vesselHeadingEventPublisher; ///< An event dispatcher for notifying when new guidance machine info messages are received + bool sendCogSogCyclically; ///< Determines if the interface will try to send the COG & SOG message cyclically + bool sendDatumCyclically; ///< Determines if the interface will try to send the Datum message cyclically + bool sendGNSSPositionDataCyclically; ///< Determines if the interface will try to send the GNSS position data message cyclically + bool sendPositionDeltaHighPrecisionRapidUpdateCyclically; ///< Determines if the interface will try to send the position delta high precision rapid update message message cyclically + bool sendPositionRapidUpdateCyclically; ///< Determines if the interface will try to send the position rapid update message cyclically + bool sendRateOfTurnCyclically; ///< Determines if the interface will try to send the rate of turn message cyclically + bool sendVesselHeadingCyclically; ///< Determines if the interface will try to send the vessel heading message cyclically + bool initialized = false; ///< Tracks if initialize has been called + }; +} // namespace isobus +#endif // NMEA2000_MESSAGE_INTERFACE_HPP diff --git a/src/thread_synchronization.hpp b/src/thread_synchronization.hpp new file mode 100644 index 0000000..2de9dd0 --- /dev/null +++ b/src/thread_synchronization.hpp @@ -0,0 +1,45 @@ +//================================================================================================ +/// @file thread_synchronization.hpp +/// +/// @brief A single header file to automatically include the correct thread synchronization +/// @author Daan Steenbergen +/// +/// @copyright 2024 The Open-Agriculture Developers +//================================================================================================ +#ifndef THREAD_SYNCHRONIZATION_HPP +#define THREAD_SYNCHRONIZATION_HPP + +#include "event_dispatcher.hpp" + +#if defined CAN_STACK_DISABLE_THREADS || defined ARDUINO + +namespace isobus +{ + /// @brief A dummy mutex class when treading is disabled. + class Mutex + { + }; + /// @brief A dummy recursive mutex class when treading is disabled. + class RecursiveMutex + { + }; +} +/// @brief Disabled LOCK_GUARD macro since threads are disabled. +#define LOCK_GUARD(type, x) + +#else + +#include +namespace isobus +{ + using Mutex = std::mutex; + using RecursiveMutex = std::recursive_mutex; +}; +/// @brief A macro to automatically lock a mutex and unlock it when the scope ends. +/// @param type The type of the mutex. +/// @param x The mutex to lock. +#define LOCK_GUARD(type, x) const std::lock_guard x##Lock(x) + +#endif + +#endif // THREAD_SYNCHRONIZATION_HPP