Skip to content

Commit

Permalink
Merge branch 'master' into 133_pr_rebase_again
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jul 31, 2024
2 parents a22feb4 + bf42a4e commit 1d755fd
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 7 deletions.
2 changes: 1 addition & 1 deletion example_10/bringup/config/rrbot_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
controller_manager:
ros__parameters:
update_rate: 1 # Hz
update_rate: 10 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
Expand Down
6 changes: 1 addition & 5 deletions example_10/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest

import launch_testing
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
Expand All @@ -50,11 +49,8 @@

# This function specifies the processes to be run for our test
# The ReadyToTest action waits for 15 second by default for the processes to
# start, if processes take more time an error is thrown. We use decorator here
# to provide timeout duration of 20 second so that processes that take longer than
# 15 seconds can start up.
# start, if processes take more time an error is thrown.
@pytest.mark.launch_test
@launch_testing.ready_to_test_action_timeout(20)
def generate_test_description():
launch_include = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ def check_controllers_running(node, cnames, namespace=""):
time.sleep(0.1)
assert all(
found.values()
), f"Controller node(s) not found: {', '.join(["ns: " + namespace_api + ", ctrl:" + cname for cname, is_found in found.items() if not is_found])}, but seeing {node.get_node_names_and_namespaces()}"
), f"Controller node(s) not found: {', '.join(['ns: ' + namespace_api + ', ctrl:' + cname for cname, is_found in found.items() if not is_found])}, but seeing {node.get_node_names_and_namespaces()}"

found = {cname: False for cname in cnames} # Define 'found' as a dictionary
start = time.time()
Expand Down

0 comments on commit 1d755fd

Please sign in to comment.