Skip to content

Commit

Permalink
Added node unit tests
Browse files Browse the repository at this point in the history
Signed-off-by: Jakub Delicat <[email protected]>
  • Loading branch information
delihus committed Oct 4, 2024
1 parent b37bb11 commit b176c7d
Show file tree
Hide file tree
Showing 9 changed files with 234 additions and 56 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/run-unit-tests.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
---
name: Run panther unit tests
name: Run unit tests

on:
workflow_dispatch:
Expand Down
12 changes: 12 additions & 0 deletions wibotic_connector_can/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,21 @@ install(TARGETS wibotic_connector_can wibotic_can_driver
DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(ros_testing REQUIRED)

# Unit tests
ament_add_gmock(
${PROJECT_NAME}_test_wibotic_can_driver_node
test/unit/test_wibotic_can_driver_node.cpp src/wibotic_can_driver_node.cpp)
target_include_directories(
${PROJECT_NAME}_test_wibotic_can_driver_node
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_link_libraries(${PROJECT_NAME}_test_wibotic_can_driver_node
wibotic_can_driver)

# Integration tests
option(TEST_INTEGRATION "Run integration tests" ON)
if(TEST_INTEGRATION)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include <memory>
#include <queue>

#include <uavcan_linux/uavcan_linux.hpp>
#include <uavcan/helpers/ostream.hpp>
#include <uavcan_linux/uavcan_linux.hpp>

#include "wibotic_connector_can/uavcan_types/wibotic/WiBoticInfo.hpp"

Expand All @@ -37,6 +37,16 @@ class WiboticCanDriverInterface
*/
virtual ~WiboticCanDriverInterface() = default;

/** *
* @param can_iface_name The name of the CAN interface.
* @param node_id The ID of the node.
* @param node_name The name of the node.
*
* @exception std::runtime_error Thrown if can interface cannot be found.
* */
virtual void SetUavCanSettings(
const std::string & can_iface_name, std::size_t node_id, const std::string & node_name) = 0;

/**
* @brief Creates the UAVCAN node.
*/
Expand All @@ -56,9 +66,9 @@ class WiboticCanDriverInterface
/**
* @brief Spins the Wibotic CAN driver.
*
* @param miliseconds The time to spin in miliseconds.
* @param milliseconds The time to spin in milliseconds.
*/
virtual void Spin(std::size_t miliseconds) = 0;
virtual void Spin(std::size_t milliseconds) = 0;

/**
* @brief Gets the WiboticInfo message.
Expand Down Expand Up @@ -86,46 +96,47 @@ class WiboticCanDriverInterface
*/
class WiboticCanDriver : public WiboticCanDriverInterface
{
typedef uavcan::MethodBinder<WiboticCanDriver*, void (WiboticCanDriver::*)(const wibotic::WiBoticInfo&)>
WiBoticInfoCallbackBinder;
typedef uavcan::MethodBinder<
WiboticCanDriver *, void (WiboticCanDriver::*)(const wibotic::WiBoticInfo &)>
WiBoticInfoCallbackBinder;

public:
/**
* @brief Constructor for the WiboticCanDriver class.
*
* @param can_iface_name The name of the CAN interface.
* @param node_id The ID of the node.
* @param node_name The name of the node.
*
* @exception std::runtime_error Thrown if can interface cannot be found.
*/
WiboticCanDriver(const std::string& can_iface_name, std::size_t node_id, const std::string& node_name);
* */
void SetUavCanSettings(
const std::string & can_iface_name, std::size_t node_id,
const std::string & node_name) override;

/**
* @brief Creates the UAVCAN node.
*/
void CreateUavCanNode() override;


void CreateWiboticInfoSubscriber() override;

/**
* @brief Activates the Wibotic CAN driver.
*
* It starts the UAVCAN node, sets it to operational mode and starts Wibotic subscriber.
*
* @exception std::runtime_error Thrown if the node or subscriber does not exist and they does not start properly.
* @exception std::runtime_error Thrown if the node or subscriber does not exist and they does not
* start properly.
*/
void Activate() override;

/**
* @brief Spins the Wibotic CAN driver.
*
* @param miliseconds The time to spin in miliseconds.
* @param milliseconds The time to spin in milliseconds.
*
* @exception std::runtime_error Thrown if the node or subscriber does not spin properly.
*/
void Spin(std::size_t miliseconds) override;
void Spin(std::size_t milliseconds) override;

/**
* @brief Gets the WiboticInfo message.
Expand All @@ -144,7 +155,7 @@ class WiboticCanDriver : public WiboticCanDriverInterface
*
* @param msg The WiboticInfo message.
*/
void WiboticInfoCallback(const wibotic::WiBoticInfo& msg);
void WiboticInfoCallback(const wibotic::WiBoticInfo & msg);

std::string can_iface_name_;
std::size_t node_id_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@

#include "wibotic_msgs/msg/wibotic_info.hpp"

// RCLCPP is compiling with C++17, so we need to define UAVCAN_CPP_VERSION to UAVCAN_CPP11
// to avoid compilation errors and silent them.
#define UAVCAN_CPP_VERSION UAVCAN_CPP11
#include "wibotic_connector_can/wibotic_can_driver.hpp"

Expand All @@ -29,28 +31,30 @@ namespace wibotic_connector_can
class WiboticCanDriverNode : public rclcpp::Node
{
public:
WiboticCanDriverNode(const std::string& node_name,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
WiboticCanDriverNode(
const std::string & node_name, WiboticCanDriverInterface::SharedPtr wibotic_can_driver,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

protected:
void DeclareParameters();
void GetParameters();

void CreateWiboticCanDriver();
wibotic::WiBoticInfo GetWiboticInfo();

void WiboticInfoTimerCallback();

wibotic_msgs::msg::WiboticInfo ConvertWiboticInfoToMsg(const wibotic::WiBoticInfo & wibotic_info);

std::string can_iface_name_;
std::size_t uavcan_node_id_;
std::string uavcan_node_name_;
float update_time_s_;

std::unique_ptr<WiboticCanDriver> wibotic_can_driver_;
WiboticCanDriverInterface::SharedPtr wibotic_can_driver_;

rclcpp::TimerBase::SharedPtr wibotic_info_timer_;
rclcpp::Publisher<wibotic_msgs::msg::WiboticInfo>::SharedPtr wibotic_info_pub_;

void WiboticInfoTimerCallback();

wibotic_msgs::msg::WiboticInfo ConvertWiboticInfoToMsg(const wibotic::WiBoticInfo& wibotic_info);
};

} // namespace wibotic_connector_can
Expand Down
1 change: 1 addition & 0 deletions wibotic_connector_can/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>rclcpp</depend>
<depend>wibotic_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>google-mock</test_depend>
<test_depend>ros_testing</test_depend>
Expand Down
4 changes: 3 additions & 1 deletion wibotic_connector_can/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,9 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

auto wibotic_can_driver_node = std::make_shared<wibotic_connector_can::WiboticCanDriverNode>("wibotic_can_driver");
auto wibotic_can_driver = std::make_shared<wibotic_connector_can::WiboticCanDriver>();
auto wibotic_can_driver_node = std::make_shared<wibotic_connector_can::WiboticCanDriverNode>(
"wibotic_can_driver", wibotic_can_driver);

try {
rclcpp::spin(wibotic_can_driver_node);
Expand Down
46 changes: 21 additions & 25 deletions wibotic_connector_can/src/wibotic_can_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,40 +16,41 @@

namespace wibotic_connector_can
{
WiboticCanDriver::WiboticCanDriver(const std::string& can_iface_name, std::size_t node_id, const std::string& node_name)
: can_iface_name_(can_iface_name), node_id_(node_id), node_name_(node_name)
void WiboticCanDriver::SetUavCanSettings(
const std::string & can_iface_name, std::size_t node_id, const std::string & node_name)
{
can_iface_name_ = can_iface_name;
node_id_ = node_id;
node_name_ = node_name;
}

void WiboticCanDriver::CreateUavCanNode()
{
uavcan_node_ = uavcan_linux::makeNode({ can_iface_name_ });
uavcan_node_ = uavcan_linux::makeNode({can_iface_name_});
uavcan_node_->setNodeID(node_id_);
uavcan_node_->setName(node_name_.c_str());
}

void WiboticCanDriver::CreateWiboticInfoSubscriber()
{
wibotic_info_uavcan_sub_ = std::make_shared<uavcan::Subscriber<wibotic::WiBoticInfo>>(*uavcan_node_);
wibotic_info_uavcan_sub_ =
std::make_shared<uavcan::Subscriber<wibotic::WiBoticInfo>>(*uavcan_node_);
}

void WiboticCanDriver::Activate()
{
if (!uavcan_node_)
{
if (!uavcan_node_) {
throw std::runtime_error("Trying to activate nonexisting node.");
}

const int sub_res =
wibotic_info_uavcan_sub_->start(WiBoticInfoCallbackBinder(this, &WiboticCanDriver::WiboticInfoCallback));
if (sub_res < 0)
{
const int sub_res = wibotic_info_uavcan_sub_->start(
WiBoticInfoCallbackBinder(this, &WiboticCanDriver::WiboticInfoCallback));
if (sub_res < 0) {
throw std::runtime_error("Failed to start the subscriber; error: " + std::to_string(sub_res));
}

const int node_start_res = uavcan_node_->start();
if (node_start_res < 0)
{
if (node_start_res < 0) {
throw std::runtime_error("Failed to start the node; error: " + std::to_string(node_start_res));
}

Expand All @@ -58,34 +59,29 @@ void WiboticCanDriver::Activate()
activated_ = true;
}

void WiboticCanDriver::Spin(std::size_t miliseconds)
void WiboticCanDriver::Spin(std::size_t milliseconds)
{
if (!uavcan_node_)
{
if (!uavcan_node_) {
throw std::runtime_error("Trying to spin nonexisting node.");
}

if (!wibotic_info_uavcan_sub_)
{
if (!wibotic_info_uavcan_sub_) {
throw std::runtime_error("Trying to spin nonexisting subscriber.");
}

if (!activated_)
{
if (!activated_) {
throw std::runtime_error("Trying to spin non-activated driver.");
}

const int res = uavcan_node_->spin(uavcan::MonotonicDuration::fromMSec(miliseconds));
if (res < 0)
{
const int res = uavcan_node_->spin(uavcan::MonotonicDuration::fromMSec(milliseconds));
if (res < 0) {
throw std::runtime_error("Failed to spin UAVCAN node, res: " + std::to_string(res));
}
}

wibotic::WiBoticInfo WiboticCanDriver::GetWiboticInfo()
{
if (wibotic_info_queue_.empty())
{
if (wibotic_info_queue_.empty()) {
throw std::runtime_error("WiBoticInfo queue is empty.");
}

Expand All @@ -94,7 +90,7 @@ wibotic::WiBoticInfo WiboticCanDriver::GetWiboticInfo()
return wibotic_info;
}

void WiboticCanDriver::WiboticInfoCallback(const wibotic::WiBoticInfo& msg)
void WiboticCanDriver::WiboticInfoCallback(const wibotic::WiBoticInfo & msg)
{
wibotic_info_queue_.push(msg);
}
Expand Down
25 changes: 17 additions & 8 deletions wibotic_connector_can/src/wibotic_can_driver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,16 @@
namespace wibotic_connector_can
{
WiboticCanDriverNode::WiboticCanDriverNode(
const std::string & node_name, const rclcpp::NodeOptions & options)
: rclcpp::Node(node_name, options)
const std::string & node_name, WiboticCanDriverInterface::SharedPtr wibotic_can_driver,
const rclcpp::NodeOptions & options)
: rclcpp::Node(node_name, options), wibotic_can_driver_(wibotic_can_driver)

{
RCLCPP_INFO(this->get_logger(), "Initializing node.");
if (!wibotic_can_driver_) {
throw std::runtime_error("Wibotic CAN driver is not initialized.");
}

DeclareParameters();
GetParameters();

Expand Down Expand Up @@ -53,24 +59,27 @@ void WiboticCanDriverNode::GetParameters()

void WiboticCanDriverNode::CreateWiboticCanDriver()
{
wibotic_can_driver_ = std::make_unique<WiboticCanDriver>(
can_iface_name_, uavcan_node_id_, uavcan_node_name_);
wibotic_can_driver_->SetUavCanSettings(can_iface_name_, uavcan_node_id_, uavcan_node_name_);
wibotic_can_driver_->CreateUavCanNode();
wibotic_can_driver_->CreateWiboticInfoSubscriber();
wibotic_can_driver_->Activate();
}

wibotic::WiBoticInfo WiboticCanDriverNode::GetWiboticInfo()
{
const auto update_time_ms = static_cast<std::size_t>(update_time_s_ * 1000);
wibotic_can_driver_->Spin(update_time_ms);
return wibotic_can_driver_->GetWiboticInfo();
}

void WiboticCanDriverNode::WiboticInfoTimerCallback()
{
if (!wibotic_can_driver_) {
throw std::runtime_error("Trying to get WiboticInfo message from nonexisting driver.");
}

try {
const auto update_time_ms = static_cast<std::size_t>(update_time_s_ * 1000);
wibotic_can_driver_->Spin(update_time_ms);
auto wibotic_info = wibotic_can_driver_->GetWiboticInfo();

auto wibotic_info = GetWiboticInfo();
wibotic_info_pub_->publish(ConvertWiboticInfoToMsg(wibotic_info));
} catch (const std::runtime_error & e) {
RCLCPP_WARN(this->get_logger(), e.what());
Expand Down
Loading

0 comments on commit b176c7d

Please sign in to comment.