Skip to content

Commit

Permalink
Merge branch 'main' into daan/vt-state-track-active-masks
Browse files Browse the repository at this point in the history
  • Loading branch information
GwnDaan authored Jan 29, 2024
2 parents c84e457 + d2d47dd commit 216f962
Show file tree
Hide file tree
Showing 26 changed files with 498 additions and 339 deletions.
17 changes: 17 additions & 0 deletions .devcontainer/Dockerfile
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
FROM mcr.microsoft.com/devcontainers/cpp:0-ubuntu-22.04
ARG REINSTALL_CMAKE_VERSION_FROM_SOURCE="none"

# Optionally install the cmake for vcpkg
COPY ./reinstall-cmake.sh /tmp/

RUN if [ "${REINSTALL_CMAKE_VERSION_FROM_SOURCE}" != "none" ]; then \
chmod +x /tmp/reinstall-cmake.sh && /tmp/reinstall-cmake.sh ${REINSTALL_CMAKE_VERSION_FROM_SOURCE}; \
fi \
&& rm -f /tmp/reinstall-cmake.sh

# [Optional] Uncomment this section to install additional vcpkg ports.
# RUN su vscode -c "${VCPKG_ROOT}/vcpkg install <your-port-name-here>"

# [Optional] Uncomment this section to install additional packages.
RUN apt-get update \
&& apt-get -y install --no-install-recommends can-utils
36 changes: 36 additions & 0 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// For format details, see https://aka.ms/devcontainer.json. For config options, see the
// README at: https://github.com/devcontainers/templates/tree/main/src/cpp
{
"name": "C++",
"build": {
"dockerfile": "Dockerfile"
},

// Features to add to the dev container. More info: https://containers.dev/features.
// "features": {},

// Configure tool-specific properties.
"customizations": {
// Configure properties specific to VS Code.
"vscode": {
"settings": {},
"extensions": [
"streetsidesoftware.code-spell-checker",
"ms-vscode.cpptools-extension-pack"
]
}
},

"runArgs": [
"--network=host"
],

// Use 'forwardPorts' to make a list of ports inside the container available locally.
// "forwardPorts": [],

// Use 'postCreateCommand' to run commands after the container is created.
"postCreateCommand": "gcc -v"

// Uncomment to connect as root instead. More info: https://aka.ms/dev-containers-non-root.
// "remoteUser": "root"
}
58 changes: 58 additions & 0 deletions .devcontainer/reinstall-cmake.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
#!/usr/bin/env bash
#-------------------------------------------------------------------------------------------------------------
# Copyright (c) Microsoft Corporation. All rights reserved.
# Licensed under the MIT License. See https://go.microsoft.com/fwlink/?linkid=2090316 for license information.
#-------------------------------------------------------------------------------------------------------------
#
set -e

CMAKE_VERSION=${1:-"none"}

if [ "${CMAKE_VERSION}" = "none" ]; then
echo "No CMake version specified, skipping CMake reinstallation"
exit 0
fi

# Cleanup temporary directory and associated files when exiting the script.
cleanup() {
EXIT_CODE=$?
set +e
if [[ -n "${TMP_DIR}" ]]; then
echo "Executing cleanup of tmp files"
rm -Rf "${TMP_DIR}"
fi
exit $EXIT_CODE
}
trap cleanup EXIT


echo "Installing CMake..."
apt-get -y purge --auto-remove cmake
mkdir -p /opt/cmake

architecture=$(dpkg --print-architecture)
case "${architecture}" in
arm64)
ARCH=aarch64 ;;
amd64)
ARCH=x86_64 ;;
*)
echo "Unsupported architecture ${architecture}."
exit 1
;;
esac

CMAKE_BINARY_NAME="cmake-${CMAKE_VERSION}-linux-${ARCH}.sh"
CMAKE_CHECKSUM_NAME="cmake-${CMAKE_VERSION}-SHA-256.txt"
TMP_DIR=$(mktemp -d -t cmake-XXXXXXXXXX)

echo "${TMP_DIR}"
cd "${TMP_DIR}"

curl -sSL "https://github.com/Kitware/CMake/releases/download/v${CMAKE_VERSION}/${CMAKE_BINARY_NAME}" -O
curl -sSL "https://github.com/Kitware/CMake/releases/download/v${CMAKE_VERSION}/${CMAKE_CHECKSUM_NAME}" -O

sha256sum -c --ignore-missing "${CMAKE_CHECKSUM_NAME}"
sh "${TMP_DIR}/${CMAKE_BINARY_NAME}" --prefix=/opt/cmake --skip-license

ln -s /opt/cmake/bin/cmake /usr/local/bin/cmake
60 changes: 39 additions & 21 deletions isobus/include/isobus/isobus/can_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,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.
Expand All @@ -52,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 Destructor for a CAN message
virtual ~CANMessage() = default;
/// @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<ControlFunction> source,
std::shared_ptr<ControlFunction> 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<std::uint8_t> data,
std::shared_ptr<ControlFunction> source,
std::shared_ptr<ControlFunction> destination,
std::uint8_t CANPort);

/// @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
Expand All @@ -69,7 +95,7 @@ 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
Expand Down Expand Up @@ -132,14 +158,6 @@ 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<ControlFunction> 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<ControlFunction> value);

/// @brief Sets the CAN ID of the message
/// @param[in] value The CAN ID for the message
void set_identifier(const CANIdentifier &value);
Expand Down Expand Up @@ -231,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<std::uint8_t> data; ///< A data buffer for the message, used when not using data chunk callbacks
std::shared_ptr<ControlFunction> source = nullptr; ///< The source control function of the message
std::shared_ptr<ControlFunction> 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<ControlFunction> source; ///< The source control function of the message
std::shared_ptr<ControlFunction> destination; ///< The destination control function of the message
std::uint8_t CANPortIndex; ///< The CAN channel index associated with the message
};

} // namespace isobus
Expand Down
31 changes: 11 additions & 20 deletions isobus/include/isobus/isobus/can_network_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <deque>
#include <list>
#include <memory>
#include <queue>

#if !defined CAN_STACK_DISABLE_THREADS && !defined ARDUINO
#include <mutex>
Expand Down Expand Up @@ -127,22 +128,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
Expand Down Expand Up @@ -299,15 +294,11 @@ namespace isobus
/// @returns A control function matching the address and CAN port passed in
std::shared_ptr<ControlFunction> 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 Informs the network manager that a control function object has been created
/// @param[in] controlFunction The control function that was created
void on_control_function_created(std::shared_ptr<ControlFunction> controlFunction);
Expand Down Expand Up @@ -344,7 +335,7 @@ 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 Checks to see if any control function didn't claim during a round of
Expand Down Expand Up @@ -391,13 +382,13 @@ namespace isobus
std::list<std::shared_ptr<PartneredControlFunction>> partneredControlFunctions; ///< A list of the partnered control functions

std::list<ParameterGroupNumberCallbackData> protocolPGNCallbacks; ///< A list of PGN callback registered by CAN protocols
std::list<CANMessage> receiveMessageList; ///< A queue of Rx messages to process
std::queue<CANMessage> receivedMessageQueue; ///< A queue of received messages to process
std::list<ControlFunctionStateCallback> controlFunctionStateCallbacks; ///< List of all control function state callbacks
std::vector<ParameterGroupNumberCallbackData> globalParameterGroupNumberCallbacks; ///< A list of all global PGN callbacks
std::vector<ParameterGroupNumberCallbackData> anyControlFunctionParameterGroupNumberCallbacks; ///< A list of all global PGN callbacks
EventDispatcher<std::shared_ptr<InternalControlFunction>> 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,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();
Expand Down
20 changes: 11 additions & 9 deletions isobus/src/can_extended_transport_protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -455,15 +455,17 @@ namespace isobus
send_end_of_session_acknowledgement(session);

// Construct the completed message
CANMessage completedMessage(0);
completedMessage.set_identifier(CANIdentifier(CANIdentifier::Type::Extended,
session->get_parameter_group_number(),
CANIdentifier::CANPriority::PriorityDefault6,
destination->get_address(),
source->get_address()));
completedMessage.set_source_control_function(source);
completedMessage.set_destination_control_function(destination);
completedMessage.set_data(data.data().begin(), static_cast<std::uint32_t>(data.size()));
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);
Expand Down
43 changes: 32 additions & 11 deletions isobus/src/can_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ControlFunction> source,
std::shared_ptr<ControlFunction> 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<std::uint8_t> data,
std::shared_ptr<ControlFunction> source,
std::shared_ptr<ControlFunction> 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;
Expand Down Expand Up @@ -109,16 +140,6 @@ namespace isobus
data.resize(length);
}

void CANMessage::set_source_control_function(std::shared_ptr<ControlFunction> value)
{
source = value;
}

void CANMessage::set_destination_control_function(std::shared_ptr<ControlFunction> value)
{
destination = value;
}

void CANMessage::set_identifier(const CANIdentifier &value)
{
identifier = value;
Expand Down
Loading

0 comments on commit 216f962

Please sign in to comment.