Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: modify some tests #1380

Merged
merged 8 commits into from May 6, 2022
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
6 changes: 6 additions & 0 deletions gazebo_plugins/CMakeLists.txt
Expand Up @@ -476,7 +476,13 @@ ament_export_dependencies(gazebo_ros)
if(BUILD_TESTING)
add_subdirectory(test)
find_package(ament_lint_auto REQUIRED)
list(APPEND AMENT_LINT_AUTO_EXCLUDE
ament_cmake_cpplint
)
ament_lint_auto_find_test_dependencies()
ament_cpplint(
FILTERS -build/include_order
)
endif()

if(NOT WIN32)
Expand Down
6 changes: 6 additions & 0 deletions gazebo_ros/CMakeLists.txt
Expand Up @@ -161,7 +161,13 @@ ament_export_dependencies(gazebo_dev)
if(BUILD_TESTING)
add_subdirectory(test)
find_package(ament_lint_auto REQUIRED)
list(APPEND AMENT_LINT_AUTO_EXCLUDE
ament_cmake_cpplint
)
ament_lint_auto_find_test_dependencies()
ament_cpplint(
FILTERS -build/include_order
)
endif()

ament_package()
Expand Down
2 changes: 1 addition & 1 deletion gazebo_ros/scripts/spawn_entity.py
Expand Up @@ -22,13 +22,13 @@
import os
import sys
from urllib.parse import SplitResult, urlsplit
from lxml import etree as ElementTree

from gazebo_msgs.msg import ModelStates
from gazebo_msgs.srv import DeleteEntity
# from gazebo_msgs.srv import SetModelConfiguration
from gazebo_msgs.srv import SpawnEntity
from geometry_msgs.msg import Pose
from lxml import etree as ElementTree
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy
Expand Down
15 changes: 9 additions & 6 deletions gazebo_ros/test/test_disable_performance_metrics.test.py
Expand Up @@ -12,22 +12,24 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from threading import Event, Thread
import time
import unittest

from gazebo_msgs.msg import PerformanceMetrics

import launch
import launch.actions

import launch_testing
import launch_testing.asserts

import pytest

import rclpy
from gazebo_msgs.msg import PerformanceMetrics
from rclpy.node import Node
from rcl_interfaces.msg import Parameter, ParameterType
from rcl_interfaces.srv import SetParameters
import time
from threading import Thread, Event
import rclpy
from rclpy.node import Node


@pytest.mark.launch_test
Expand Down Expand Up @@ -89,12 +91,13 @@ def test_parameter_disable(self):

node.start_subscriber()
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
assert not msgs_received_flag, f'Received messages after\
assert not msgs_received_flag, 'Received messages after\
setting enable_performance_metrics parameter to False, test failed'
rclpy.shutdown()


class MakeTestNode(Node):

def __init__(self, name):
"""Initialize node and counters."""
super().__init__(name)
Expand Down
2 changes: 1 addition & 1 deletion gazebo_ros/test/test_sim_time.cpp
Expand Up @@ -62,7 +62,7 @@ TEST_F(TestSimTime, TestClock)
std::vector<ClockMsg::SharedPtr> msgs;
std::vector<rclcpp::Time> times;
auto sub = node->create_subscription<ClockMsg>(
"/clock", rclcpp::SystemDefaultsQoS(),
"/clock", rclcpp::ClockQoS(),
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
[&](ClockMsg::SharedPtr _msg) {
msgs.push_back(_msg);
times.push_back(node->now());
Expand Down