diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py index b58676cd7..983d6d312 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py @@ -17,7 +17,6 @@ import os import subprocess # nosec B404 import glob -from shutil import which import defusedxml.ElementTree from ament_index_python import get_package_share_directory from pathlib import Path @@ -242,7 +241,7 @@ def find_mesh(self, mesh_name: str, entity_name: str) -> str: print(f'[{entity_name}] unrecognized model file definition: {mesh_name}') return None - def get_env(): + def get_env(): # pylint: disable=no-method-argument if "ROS_DISTRO" not in os.environ: raise ValueError("ROS_DISTRO not set.") diff --git a/scenario_execution_ros/scenarios/test/test_ros_service_call.osc b/scenario_execution_ros/scenarios/test/test_ros_service_call.osc index 99726e599..e364f45e6 100644 --- a/scenario_execution_ros/scenarios/test/test_ros_service_call.osc +++ b/scenario_execution_ros/scenarios/test/test_ros_service_call.osc @@ -8,5 +8,4 @@ scenario test_ros_service_call: keep(it.service_name == '/bla') keep(it.service_type == 'std_srvs.srv.SetBool') keep(it.data == '{\"data\": True}') - wait elapsed(2s) - emit_arrival: emit end + emit end diff --git a/scenario_execution_ros/scenarios/test/test_ros_service_call_blocking.osc b/scenario_execution_ros/scenarios/test/test_ros_service_call_blocking.osc index 4a1e965ae..e4b47d7a8 100644 --- a/scenario_execution_ros/scenarios/test/test_ros_service_call_blocking.osc +++ b/scenario_execution_ros/scenarios/test/test_ros_service_call_blocking.osc @@ -9,65 +9,34 @@ scenario test_ros_service_call_blocking: keep(it.service_name == '/bla_service') keep(it.service_type == 'std_srvs.srv.SetBool') keep(it.data == '{\"data\": True}') - wait elapsed(10s) emit end test2: serial: topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 0}') - wait elapsed(1s) + wait elapsed(2s) topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 1}') - wait elapsed(1s) + wait elapsed(2s) topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 2}') - wait elapsed(1s) + wait elapsed(2s) topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 3}') - wait elapsed(1s) + wait elapsed(2s) topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 4}') - wait elapsed(1s) + wait elapsed(2s) topic_publish() with: keep(it.topic_name == '/bla') keep(it.topic_type == 'std_msgs.msg.Int32') keep(it.value == '{\"data\": 5}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 6}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 7}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 8}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 9}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 10}') - wait elapsed(1s) - topic_publish() with: - keep(it.topic_name == '/bla') - keep(it.topic_type == 'std_msgs.msg.Int32') - keep(it.value == '{\"data\": 11}') diff --git a/scenario_execution_ros/scenarios/test/test_ros_set_node_parameter.osc b/scenario_execution_ros/scenarios/test/test_ros_set_node_parameter.osc index 7cce2b813..7e1f433da 100644 --- a/scenario_execution_ros/scenarios/test/test_ros_set_node_parameter.osc +++ b/scenario_execution_ros/scenarios/test/test_ros_set_node_parameter.osc @@ -12,4 +12,3 @@ scenario test_ros_set_node_parameter: keep(it.node_name == '/test_node') keep(it.parameter_name == 'testBoolParam') keep(it.parameter_value == 'True') - wait elapsed(3s) diff --git a/scenario_execution_ros/test/test_ros_service_call_blocking.py b/scenario_execution_ros/test/test_ros_service_call_blocking.py index 885773800..a67e1d622 100644 --- a/scenario_execution_ros/test/test_ros_service_call_blocking.py +++ b/scenario_execution_ros/test/test_ros_service_call_blocking.py @@ -85,6 +85,6 @@ def test_success(self): for elem in self.received_msgs[1:]: self.assertGreater(elem[1].data, prev_elem[1].data) time_since_last = elem[0]-prev_elem[0] - self.assertGreaterEqual(time_since_last, rclpy.duration.Duration(seconds=0.5)) - self.assertLessEqual(time_since_last, rclpy.duration.Duration(seconds=1.7)) + self.assertGreaterEqual(time_since_last, rclpy.duration.Duration(seconds=1.0)) + self.assertLessEqual(time_since_last, rclpy.duration.Duration(seconds=3.0)) prev_elem = elem diff --git a/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py b/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py index 295363dd8..cdd00ea78 100644 --- a/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py +++ b/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py @@ -18,7 +18,7 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration +from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration, PythonExpression, EnvironmentVariable from launch.substitutions.path_join_substitution import PathJoinSubstitution from launch.conditions import IfCondition, UnlessCondition diff --git a/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py b/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py index 2183e28a9..362eeadff 100644 --- a/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py +++ b/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py @@ -34,7 +34,7 @@ def generate_launch_description(): tf_to_pose_publisher_dir = get_package_share_directory('tf_to_pose_publisher') try: nav2_minimal_tb4_sim_dir = get_package_share_directory('nav2_minimal_tb4_sim') - except: + except Exception: # pylint: disable=broad-except nav2_minimal_tb4_sim_dir = "" scenario = LaunchConfiguration('scenario')