Skip to content

Commit 0b405ec

Browse files
authored
test: include integration tests into coverage report (#69)
* test: add integration tests to coverage calculation * remove dead code
1 parent fc04e8f commit 0b405ec

File tree

10 files changed

+100
-284
lines changed

10 files changed

+100
-284
lines changed

.github/workflows/ci.yml

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -93,15 +93,16 @@ jobs:
9393
--cmake-args -DCMAKE_BUILD_TYPE=Debug -DENABLE_COVERAGE=ON \
9494
--event-handlers console_direct+
9595
96-
- name: Run unit tests only
97-
# Run only unit tests for coverage:
96+
- name: Run unit and integration tests for coverage
97+
# Run all tests for coverage (excluding linters):
9898
# -LE linter: exclude linters by label
99-
# -E integration: exclude integration tests by name regex
99+
# Integration tests now capture coverage via GCOV_PREFIX env vars
100+
# set in test launch files (test_integration.test.py, test_cors.test.py)
100101
run: |
101102
source /opt/ros/jazzy/setup.bash
102103
source install/setup.bash
103104
colcon test \
104-
--ctest-args -LE linter -E integration \
105+
--ctest-args -LE linter \
105106
--event-handlers console_direct+
106107
107108
- name: Generate coverage report
@@ -150,7 +151,7 @@ jobs:
150151
with:
151152
token: ${{ secrets.CODECOV_TOKEN }}
152153
files: coverage.info
153-
flags: unittests
154+
flags: unittests,integration
154155
name: ros2_medkit-coverage
155156
fail_ci_if_error: true
156157
verbose: true

src/ros2_medkit_gateway/design/index.rst

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,6 @@ The following diagram shows the relationships between the main components of the
7676
+ list_parameters(): ParameterResult
7777
+ get_parameter(): ParameterResult
7878
+ set_parameter(): ParameterResult
79-
+ describe_parameter(): ParameterResult
80-
+ is_node_available(): bool
8179
}
8280

8381
class NativeTopicSampler {

src/ros2_medkit_gateway/include/ros2_medkit_gateway/configuration_manager.hpp

Lines changed: 0 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -57,17 +57,6 @@ class ConfigurationManager {
5757
/// @return ParameterResult with {name, value, type}
5858
ParameterResult set_parameter(const std::string & node_name, const std::string & param_name, const json & value);
5959

60-
/// Describe a parameter (get metadata)
61-
/// @param node_name Fully qualified node name
62-
/// @param param_name Parameter name
63-
/// @return ParameterResult with parameter descriptor info
64-
ParameterResult describe_parameter(const std::string & node_name, const std::string & param_name);
65-
66-
/// Check if a node exists and is reachable for parameter operations
67-
/// @param node_name Fully qualified node name
68-
/// @return true if node parameters are accessible
69-
bool is_node_available(const std::string & node_name);
70-
7160
private:
7261
/// Get or create a SyncParametersClient for the given node
7362
std::shared_ptr<rclcpp::SyncParametersClient> get_param_client(const std::string & node_name);

src/ros2_medkit_gateway/include/ros2_medkit_gateway/data_access_manager.hpp

Lines changed: 0 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -59,15 +59,6 @@ class DataAccessManager {
5959
*/
6060
json get_topic_sample_with_fallback(const std::string & topic_name, double timeout_sec = -1.0);
6161

62-
/**
63-
* @brief Get component data with fallback to metadata for unavailable topics
64-
*
65-
* @param component_namespace Component's namespace
66-
* @param timeout_sec Timeout per topic. Use -1.0 to use the topic_sample_timeout_sec parameter (default)
67-
* @return JSON array with topic data/metadata
68-
*/
69-
json get_component_data_with_fallback(const std::string & component_namespace, double timeout_sec = -1.0);
70-
7162
/**
7263
* @brief Get the type introspection instance
7364
*/
@@ -84,36 +75,6 @@ class DataAccessManager {
8475
return native_sampler_.get();
8576
}
8677

87-
/**
88-
* @brief Get component data using native rclcpp APIs (fast, no CLI overhead)
89-
*
90-
* This method uses the NativeTopicSampler to:
91-
* - Discover topics via node_->get_topic_names_and_types() instead of `ros2 topic list`
92-
* - Check publisher counts before sampling to skip idle topics immediately
93-
* - Return metadata for topics without publishers without waiting for timeout
94-
*
95-
* @param component_namespace Component's namespace (e.g., "/powertrain/engine")
96-
* @param timeout_sec Timeout per topic for topics that have publishers
97-
* @return JSON array with topic data/metadata
98-
* @deprecated Use get_component_data_by_fqn instead for accurate topic discovery
99-
*/
100-
json get_component_data_native(const std::string & component_namespace, double timeout_sec = 1.0);
101-
102-
/**
103-
* @brief Get component data by fully qualified name using topic map
104-
*
105-
* This method finds all topics that the component publishes or subscribes to
106-
* by building a component-topic map from the ROS graph. This is more accurate
107-
* than namespace-based filtering because:
108-
* - A node can publish/subscribe to topics outside its namespace
109-
* - Topics like /clock, /tf, /diagnostics are in root namespace but used by many nodes
110-
*
111-
* @param component_fqn Component's fully qualified name (e.g., "/ros2_medkit_gateway")
112-
* @param timeout_sec Timeout per topic for topics that have publishers
113-
* @return JSON array with topic data/metadata for all topics this component interacts with
114-
*/
115-
json get_component_data_by_fqn(const std::string & component_fqn, double timeout_sec = 1.0);
116-
11778
/**
11879
* @brief Get single topic sample using native rclcpp APIs
11980
*
@@ -134,11 +95,6 @@ class DataAccessManager {
13495
}
13596

13697
private:
137-
/**
138-
* @brief Find all topics under a given namespace using native API
139-
*/
140-
std::vector<std::string> find_component_topics_native(const std::string & component_namespace);
141-
14298
/**
14399
* @brief Convert TopicSampleResult to JSON with type info enrichment
144100
*/

src/ros2_medkit_gateway/include/ros2_medkit_gateway/type_introspection.hpp

Lines changed: 0 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -35,16 +35,6 @@ struct TopicTypeInfo {
3535
nlohmann::json default_value; ///< Template with default values
3636
};
3737

38-
/**
39-
* @brief Metadata about a topic (without actual data)
40-
*/
41-
struct TopicMetadata {
42-
std::string topic_path; ///< Full topic path (e.g., "/powertrain/engine/temperature")
43-
std::string type_name; ///< Message type name
44-
int publisher_count{0}; ///< Number of publishers
45-
int subscriber_count{0}; ///< Number of subscribers
46-
};
47-
4838
/**
4939
* @brief Provides type introspection capabilities for ROS 2 message types
5040
*
@@ -73,17 +63,6 @@ class TypeIntrospection {
7363
TypeIntrospection(TypeIntrospection &&) = delete;
7464
TypeIntrospection & operator=(TypeIntrospection &&) = delete;
7565

76-
/**
77-
* @brief Get metadata for a topic (type, publisher/subscriber counts)
78-
*
79-
* This method is fast and doesn't require the topic to be publishing.
80-
*
81-
* @param topic_path Full path to the topic (e.g., "/powertrain/engine/temperature")
82-
* @return TopicMetadata containing topic information
83-
* @throws std::runtime_error if topic info cannot be retrieved
84-
*/
85-
TopicMetadata get_topic_metadata(const std::string & topic_path);
86-
8766
/**
8867
* @brief Get full type information including schema (with caching)
8968
*
@@ -115,11 +94,6 @@ class TypeIntrospection {
11594
*/
11695
nlohmann::json get_type_schema(const std::string & type_name);
11796

118-
/**
119-
* @brief Clear the type info cache
120-
*/
121-
void clear_cache();
122-
12397
private:
12498
std::string scripts_path_; ///< Path to helper scripts
12599
std::unique_ptr<ROS2CLIWrapper> cli_wrapper_; ///< CLI wrapper for commands

src/ros2_medkit_gateway/src/configuration_manager.cpp

Lines changed: 0 additions & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -49,11 +49,6 @@ std::shared_ptr<rclcpp::SyncParametersClient> ConfigurationManager::get_param_cl
4949
return client;
5050
}
5151

52-
bool ConfigurationManager::is_node_available(const std::string & node_name) {
53-
auto client = get_param_client(node_name);
54-
return client->wait_for_service(1s);
55-
}
56-
5752
ParameterResult ConfigurationManager::list_parameters(const std::string & node_name) {
5853
ParameterResult result;
5954

@@ -192,62 +187,6 @@ ParameterResult ConfigurationManager::set_parameter(const std::string & node_nam
192187
return result;
193188
}
194189

195-
ParameterResult ConfigurationManager::describe_parameter(const std::string & node_name,
196-
const std::string & param_name) {
197-
ParameterResult result;
198-
199-
try {
200-
auto client = get_param_client(node_name);
201-
202-
if (!client->wait_for_service(2s)) {
203-
result.success = false;
204-
result.error_message = "Parameter service not available for node: " + node_name;
205-
return result;
206-
}
207-
208-
auto descriptors = client->describe_parameters({param_name});
209-
if (descriptors.empty()) {
210-
result.success = false;
211-
result.error_message = "Parameter not found: " + param_name;
212-
return result;
213-
}
214-
215-
const auto & desc = descriptors[0];
216-
json desc_obj;
217-
desc_obj["name"] = desc.name;
218-
desc_obj["type"] = parameter_type_to_string(static_cast<rclcpp::ParameterType>(desc.type));
219-
desc_obj["description"] = desc.description;
220-
desc_obj["read_only"] = desc.read_only;
221-
222-
// Add constraints if available
223-
if (!desc.additional_constraints.empty()) {
224-
desc_obj["additional_constraints"] = desc.additional_constraints;
225-
}
226-
if (!desc.floating_point_range.empty()) {
227-
json range;
228-
range["from_value"] = desc.floating_point_range[0].from_value;
229-
range["to_value"] = desc.floating_point_range[0].to_value;
230-
range["step"] = desc.floating_point_range[0].step;
231-
desc_obj["floating_point_range"] = range;
232-
}
233-
if (!desc.integer_range.empty()) {
234-
json range;
235-
range["from_value"] = desc.integer_range[0].from_value;
236-
range["to_value"] = desc.integer_range[0].to_value;
237-
range["step"] = desc.integer_range[0].step;
238-
desc_obj["integer_range"] = range;
239-
}
240-
241-
result.success = true;
242-
result.data = desc_obj;
243-
} catch (const std::exception & e) {
244-
result.success = false;
245-
result.error_message = std::string("Failed to describe parameter: ") + e.what();
246-
}
247-
248-
return result;
249-
}
250-
251190
std::string ConfigurationManager::parameter_type_to_string(rclcpp::ParameterType type) {
252191
switch (type) {
253192
case rclcpp::ParameterType::PARAMETER_BOOL:

src/ros2_medkit_gateway/src/data_access_manager.cpp

Lines changed: 0 additions & 87 deletions
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,9 @@
1414

1515
#include "ros2_medkit_gateway/data_access_manager.hpp"
1616

17-
#include <algorithm>
1817
#include <ament_index_cpp/get_package_share_directory.hpp>
1918
#include <chrono>
2019
#include <cmath>
21-
#include <future>
2220
#include <sstream>
2321

2422
#include "ros2_medkit_gateway/exceptions.hpp"
@@ -105,25 +103,6 @@ json DataAccessManager::get_topic_sample_with_fallback(const std::string & topic
105103
return get_topic_sample_native(topic_name, effective_timeout);
106104
}
107105

108-
json DataAccessManager::get_component_data_with_fallback(const std::string & component_namespace, double timeout_sec) {
109-
// Use configured parameter if timeout_sec is negative (default)
110-
double effective_timeout = (timeout_sec < 0) ? topic_sample_timeout_sec_ : timeout_sec;
111-
// Always use native sampling - much faster for idle topics
112-
return get_component_data_native(component_namespace, effective_timeout);
113-
}
114-
115-
std::vector<std::string> DataAccessManager::find_component_topics_native(const std::string & component_namespace) {
116-
auto topics = native_sampler_->discover_topics(component_namespace);
117-
std::vector<std::string> topic_names;
118-
topic_names.reserve(topics.size());
119-
for (const auto & topic : topics) {
120-
topic_names.push_back(topic.name);
121-
}
122-
RCLCPP_INFO(node_->get_logger(), "Found %zu topics under namespace '%s' (native)", topic_names.size(),
123-
component_namespace.c_str());
124-
return topic_names;
125-
}
126-
127106
json DataAccessManager::sample_result_to_json(const TopicSampleResult & sample) {
128107
json result;
129108
result["topic"] = sample.topic_name;
@@ -183,70 +162,4 @@ json DataAccessManager::get_topic_sample_native(const std::string & topic_name,
183162
throw TopicNotAvailableException(topic_name);
184163
}
185164

186-
json DataAccessManager::get_component_data_native(const std::string & component_namespace, double timeout_sec) {
187-
json result = json::array();
188-
189-
// Use native discovery
190-
auto topics = find_component_topics_native(component_namespace);
191-
192-
if (topics.empty()) {
193-
RCLCPP_WARN(node_->get_logger(), "No topics found under namespace '%s'", component_namespace.c_str());
194-
return result;
195-
}
196-
197-
// Use native parallel sampling with publisher count optimization
198-
auto samples = native_sampler_->sample_topics_parallel(topics, timeout_sec, max_parallel_samples_);
199-
200-
for (const auto & sample : samples) {
201-
try {
202-
result.push_back(sample_result_to_json(sample));
203-
} catch (const std::exception & e) {
204-
RCLCPP_WARN(node_->get_logger(), "Failed to convert sample for '%s': %s", sample.topic_name.c_str(), e.what());
205-
}
206-
}
207-
208-
return result;
209-
}
210-
211-
json DataAccessManager::get_component_data_by_fqn(const std::string & component_fqn, double timeout_sec) {
212-
json result = json::array();
213-
214-
// Get topics this component publishes/subscribes to using the topic map
215-
auto component_topics = native_sampler_->get_component_topics(component_fqn);
216-
217-
// Combine publishes and subscribes into unique set of topics
218-
std::set<std::string> all_topics;
219-
for (const auto & topic : component_topics.publishes) {
220-
all_topics.insert(topic);
221-
}
222-
for (const auto & topic : component_topics.subscribes) {
223-
all_topics.insert(topic);
224-
}
225-
226-
if (all_topics.empty()) {
227-
RCLCPP_WARN(node_->get_logger(), "No topics found for component '%s'", component_fqn.c_str());
228-
return result;
229-
}
230-
231-
RCLCPP_INFO(node_->get_logger(), "Found %zu topics for component '%s' (publishes: %zu, subscribes: %zu)",
232-
all_topics.size(), component_fqn.c_str(), component_topics.publishes.size(),
233-
component_topics.subscribes.size());
234-
235-
// Convert set to vector for parallel sampling
236-
std::vector<std::string> topics_vec(all_topics.begin(), all_topics.end());
237-
238-
// Use native parallel sampling with publisher count optimization
239-
auto samples = native_sampler_->sample_topics_parallel(topics_vec, timeout_sec, max_parallel_samples_);
240-
241-
for (const auto & sample : samples) {
242-
try {
243-
result.push_back(sample_result_to_json(sample));
244-
} catch (const std::exception & e) {
245-
RCLCPP_WARN(node_->get_logger(), "Failed to convert sample for '%s': %s", sample.topic_name.c_str(), e.what());
246-
}
247-
}
248-
249-
return result;
250-
}
251-
252165
} // namespace ros2_medkit_gateway

0 commit comments

Comments
 (0)