Skip to content

Commit 90cf593

Browse files
authored
Merge branch 'master' into fix/test_init
2 parents 0672ab6 + da81eb1 commit 90cf593

File tree

9 files changed

+719
-197
lines changed

9 files changed

+719
-197
lines changed

controller_manager/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -247,6 +247,7 @@ if(BUILD_TESTING)
247247
install(FILES test/test_ros2_control_node.yaml
248248
DESTINATION test)
249249
ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py)
250+
ament_add_pytest_test(test_test_utils test/test_test_utils.py)
250251
endif()
251252

252253
install(

controller_manager/controller_manager/spawner.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,10 @@ def main(args=None):
182182
ros_home = os.getenv("ROS_HOME", os.path.join(os.path.expanduser("~"), ".ros"))
183183
ros_control_lock_dir = os.path.join(ros_home, "locks")
184184
if not os.path.exists(ros_control_lock_dir):
185-
os.makedirs(ros_control_lock_dir)
185+
try:
186+
os.makedirs(ros_control_lock_dir)
187+
except FileExistsError:
188+
pass
186189
lock = FileLock(f"{ros_control_lock_dir}/ros2-control-controller-spawner.lock")
187190
max_retries = 5
188191
retry_delay = 3 # seconds

controller_manager/test/test_ros2_control_node_launch.py

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -37,16 +37,13 @@
3737
from launch_testing.actions import ReadyToTest
3838
import launch_testing.markers
3939
import launch_ros.actions
40-
from sensor_msgs.msg import JointState
4140

4241
import rclpy
4342
from controller_manager.test_utils import (
4443
check_controllers_running,
45-
check_if_js_published,
4644
check_node_running,
4745
)
4846
from controller_manager.launch_utils import generate_controllers_spawner_launch_description
49-
import threading
5047

5148

5249
# Executes the given launch file and checks if all nodes can be started
@@ -105,31 +102,13 @@ def setUp(self):
105102
def tearDown(self):
106103
self.node.destroy_node()
107104

108-
def timer_callback(self):
109-
js_msg = JointState()
110-
js_msg.name = ["joint0"]
111-
js_msg.position = [0.0]
112-
self.pub.publish(js_msg)
113-
114-
def publish_joint_states(self):
115-
self.pub = self.node.create_publisher(JointState, "/joint_states", 10)
116-
self.timer = self.node.create_timer(1.0, self.timer_callback)
117-
rclpy.spin(self.node)
118-
119105
def test_node_start(self):
120106
check_node_running(self.node, "controller_manager")
121107

122108
def test_controllers_start(self):
123109
cnames = ["ctrl_with_parameters_and_type"]
124110
check_controllers_running(self.node, cnames, state="active")
125111

126-
def test_check_if_msgs_published(self):
127-
# we don't have a joint_state_broadcaster in this repo,
128-
# publish joint states manually to test check_if_js_published
129-
thread = threading.Thread(target=self.publish_joint_states)
130-
thread.start()
131-
check_if_js_published("/joint_states", ["joint0"])
132-
133112

134113
@launch_testing.post_shutdown_test()
135114
# These tests are run after the processes in generate_test_description() have shutdown.
Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
# Copyright (c) 2025 AIT - Austrian Institute of Technology GmbH
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the {copyright_holder} nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
#
29+
# Author: Christoph Froehlich
30+
31+
import unittest
32+
from sensor_msgs.msg import JointState
33+
34+
import rclpy
35+
from controller_manager.test_utils import (
36+
check_if_js_published,
37+
)
38+
import threading
39+
40+
41+
# This is our test fixture. Each method is a test case.
42+
# These run alongside the processes specified in generate_test_description()
43+
class TestFixture(unittest.TestCase):
44+
@classmethod
45+
def setUpClass(cls):
46+
rclpy.init()
47+
48+
@classmethod
49+
def tearDownClass(cls):
50+
rclpy.shutdown()
51+
52+
def setUp(self):
53+
self.node = rclpy.create_node("test_node")
54+
55+
def tearDown(self):
56+
self.node.destroy_node()
57+
58+
def timer_callback(self):
59+
js_msg = JointState()
60+
js_msg.name = ["joint0"]
61+
js_msg.position = [0.0]
62+
self.pub.publish(js_msg)
63+
64+
def publish_joint_states(self):
65+
self.pub = self.node.create_publisher(JointState, "/joint_states", 10)
66+
self.timer = self.node.create_timer(1.0, self.timer_callback)
67+
rclpy.spin(self.node)
68+
69+
def test_check_if_msgs_published(self):
70+
# we don't have a joint_state_broadcaster in this repo,
71+
# publish joint states manually to test check_if_js_published
72+
thread = threading.Thread(target=self.publish_joint_states)
73+
thread.start()
74+
check_if_js_published("/joint_states", ["joint0"])
75+
76+
# Note: Other test cases are in test_ros2_control_node_launch.py

hardware_interface/include/hardware_interface/hardware_component_interface.hpp

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -697,6 +697,16 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
697697
lifecycle_state_ = new_state;
698698
}
699699

700+
/// Does the state interface exist?
701+
/**
702+
* \param[in] interface_name The name of the state interface.
703+
* \return true if the state interface exists, false otherwise.
704+
*/
705+
bool has_state(const std::string & interface_name) const
706+
{
707+
return hardware_states_.find(interface_name) != hardware_states_.end();
708+
}
709+
700710
/// Set the value of a state interface.
701711
/**
702712
* \tparam T The type of the value to be stored.
@@ -757,6 +767,16 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
757767
return opt_value.value();
758768
}
759769

770+
/// Does the command interface exist?
771+
/**
772+
* \param[in] interface_name The name of the command interface.
773+
* \return true if the command interface exists, false otherwise.
774+
*/
775+
bool has_command(const std::string & interface_name) const
776+
{
777+
return hardware_commands_.find(interface_name) != hardware_commands_.end();
778+
}
779+
760780
/// Set the value of a command interface.
761781
/**
762782
* \tparam T The type of the value to be stored.

hardware_interface/include/mock_components/generic_system.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,9 @@ class GenericSystem : public hardware_interface::SystemInterface
4545
CallbackReturn on_init(
4646
const hardware_interface::HardwareComponentInterfaceParams & params) override;
4747

48+
hardware_interface::CallbackReturn on_configure(
49+
const rclcpp_lifecycle::State & previous_state) override;
50+
4851
hardware_interface::CallbackReturn on_activate(
4952
const rclcpp_lifecycle::State & previous_state) override;
5053

@@ -79,10 +82,6 @@ class GenericSystem : public hardware_interface::SystemInterface
7982
hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT};
8083
std::vector<std::string> skip_interfaces_;
8184

82-
std::vector<std::string> other_interfaces_;
83-
std::vector<std::string> sensor_interfaces_;
84-
std::vector<std::string> gpio_mock_interfaces_;
85-
8685
private:
8786
bool populate_interfaces(
8887
const std::vector<hardware_interface::ComponentInfo> & components,

0 commit comments

Comments
 (0)