Apartment Navigation By Classic Wheeled Robot
Comprehensive Production Grade Repository For Apartment Navigation Project (Inspired By Udacity Course)
 
Loading...
Searching...
No Matches
ProcessImageTest Class Reference

Integration tests for the ProcessImage ROS 2 client node. More...

Inheritance diagram for ProcessImageTest:

Protected Member Functions

void SetUp () override
 The SetUp function creates a stub service node, a publisher node, and a client node, and waits for the client node to discover the stub service before publishing images.
 
void TearDown () override
 The TearDown function removes specific nodes from an executor.
 
void spinFor (std::chrono::milliseconds duration)
 The function spinFor spins the executor for a specified duration using a steady clock until the deadline is reached.
 
void publishAndWaitForCall (const sensor_msgs::msg::Image &img, uint8_t expectedCallCount)
 The function publishAndWaitForCall publishes an image and waits for a specified number of expected calls before timing out.
 

Protected Attributes

std::shared_ptr< rclcpp::Node > m_stubNode
 Stub node hosting the fake DriveToTarget service.
 
std::shared_ptr< rclcpp::Node > m_pubNode
 Publisher node that sends test images.
 
std::shared_ptr< robot_control::ball_chaser::ProcessImagem_client
 ProcessImage node under test.
 
rclcpp::Service< DriveToTarget >::SharedPtr m_service
 Fake DriveToTarget service that captures requests.
 
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr m_pub
 Publisher for the test image topic.
 
rclcpp::executors::SingleThreadedExecutor m_executor
 Executor to spin all nodes during tests.
 
DriveToTarget::Request m_lastRequest
 Most recent request received by the fake service.
 
uint8_t m_callCount {0}
 Number of times the fake service has been called.
 

Detailed Description

Integration tests for the ProcessImage ROS 2 client node.

Tests verify that ProcessImage correctly:

  • Calls DriveToTarget with angular velocity when the ball is left or right
  • Calls DriveToTarget with linear velocity when the ball is centered
  • Sends a stop command exactly once when the ball disappears after movement
  • Does not call the service when no ball is detected and the robot was already stopped

Member Function Documentation

◆ publishAndWaitForCall()

void ProcessImageTest::publishAndWaitForCall ( const sensor_msgs::msg::Image & img,
uint8_t expectedCallCount )
inlineprotected

The function publishAndWaitForCall publishes an image and waits for a specified number of expected calls before timing out.

Parameters
imgThe img parameter is of type sensor_msgs::msg::Image, which is a message type used in ROS (Robot Operating System) for representing images. It likely contains data such as image height, width, encoding type, and pixel data. In this function, the img parameter
expectedCallCountThe expectedCallCount parameter represents the number of times a certain function or method is expected to be called before the publishAndWaitForCall function completes its execution. This parameter is used to wait until the expected number of calls have been made before proceeding further in the code.

◆ spinFor()

void ProcessImageTest::spinFor ( std::chrono::milliseconds duration)
inlineprotected

The function spinFor spins the executor for a specified duration using a steady clock until the deadline is reached.

Parameters
durationThe duration parameter in the spinFor function represents the amount of time for which the function will keep spinning the executor. It is of type std::chrono::milliseconds, which means it expects a duration specified in milliseconds.

The documentation for this class was generated from the following file: