|
| 1 | +/* Copyright 2020 Open Source Robotics Foundation, Inc. |
| 2 | + * |
| 3 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | + * you may not use this file except in compliance with the License. |
| 5 | + * You may obtain a copy of the License at |
| 6 | + * |
| 7 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | + * |
| 9 | + * Unless required by applicable law or agreed to in writing, software |
| 10 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | + * See the License for the specific language governing permissions and |
| 13 | + * limitations under the License. |
| 14 | + */ |
| 15 | + |
| 16 | +package org.ros2.rcljava.time; |
| 17 | + |
| 18 | +import static org.junit.Assert.assertTrue; |
| 19 | +import static org.junit.Assert.assertFalse; |
| 20 | + |
| 21 | +import org.junit.AfterClass; |
| 22 | +import org.junit.BeforeClass; |
| 23 | +import org.junit.Test; |
| 24 | + |
| 25 | +import org.junit.runner.RunWith; |
| 26 | + |
| 27 | +import static org.mockito.Mockito.*; |
| 28 | +import org.mockito.Mock; |
| 29 | +import org.mockito.junit.MockitoJUnitRunner; |
| 30 | + |
| 31 | +import org.ros2.rcljava.consumers.Consumer; |
| 32 | +import org.ros2.rcljava.RCLJava; |
| 33 | +import org.ros2.rcljava.node.Node; |
| 34 | +import org.ros2.rcljava.parameters.ParameterVariant; |
| 35 | +import org.ros2.rcljava.subscription.Subscription; |
| 36 | +import org.ros2.rcljava.time.TimeSource; |
| 37 | + |
| 38 | +@RunWith(MockitoJUnitRunner.StrictStubs.class) |
| 39 | +public class TimeSourceTest { |
| 40 | + @Mock |
| 41 | + private Node mockedNode; |
| 42 | + |
| 43 | + @Mock |
| 44 | + private Clock mockedClock; |
| 45 | + |
| 46 | + @Mock |
| 47 | + private Subscription mockSubscription; |
| 48 | + |
| 49 | + @BeforeClass |
| 50 | + public static void setupOnce() throws Exception { |
| 51 | + // Just to quiet down warnings |
| 52 | + org.apache.log4j.BasicConfigurator.configure(); |
| 53 | + |
| 54 | + RCLJava.rclJavaInit(); |
| 55 | + } |
| 56 | + |
| 57 | + @AfterClass |
| 58 | + public static void tearDownOnce() { |
| 59 | + RCLJava.shutdown(); |
| 60 | + } |
| 61 | + |
| 62 | + @Test |
| 63 | + public final void testEmptyConstructor() { |
| 64 | + TimeSource timeSource = new TimeSource(); |
| 65 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 66 | + } |
| 67 | + |
| 68 | + @Test |
| 69 | + public final void testConstructorWithNode() { |
| 70 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false)); |
| 71 | + |
| 72 | + TimeSource timeSource = new TimeSource(mockedNode); |
| 73 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 74 | + } |
| 75 | + |
| 76 | + @Test |
| 77 | + public final void testAttachNodeUseSimTimeFalse() { |
| 78 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false)); |
| 79 | + |
| 80 | + TimeSource timeSource = new TimeSource(); |
| 81 | + timeSource.attachNode(mockedNode); |
| 82 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 83 | + } |
| 84 | + |
| 85 | + @Test |
| 86 | + public final void testAttachNodeUseSimTimeTrue() { |
| 87 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true)); |
| 88 | + |
| 89 | + TimeSource timeSource = new TimeSource(); |
| 90 | + timeSource.attachNode(mockedNode); |
| 91 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 92 | + } |
| 93 | + |
| 94 | + @Test |
| 95 | + public final void testAttachNodeTwice() { |
| 96 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true)); |
| 97 | + |
| 98 | + TimeSource timeSource = new TimeSource(); |
| 99 | + timeSource.attachNode(mockedNode); |
| 100 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 101 | + |
| 102 | + // Attach the same node again |
| 103 | + timeSource.attachNode(mockedNode); |
| 104 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 105 | + } |
| 106 | + |
| 107 | + @Test |
| 108 | + public final void testDetachNode() { |
| 109 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true)); |
| 110 | + |
| 111 | + // Attaches node with ROS time active |
| 112 | + TimeSource timeSource = new TimeSource(mockedNode); |
| 113 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 114 | + |
| 115 | + timeSource.detachNode(); |
| 116 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 117 | + |
| 118 | + // Calling detach again shouldn't change anything |
| 119 | + timeSource.detachNode(); |
| 120 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 121 | + } |
| 122 | + |
| 123 | + @Test |
| 124 | + public final void testAttachClock() { |
| 125 | + when(mockedClock.getClockType()).thenReturn(ClockType.ROS_TIME); |
| 126 | + |
| 127 | + TimeSource timeSource = new TimeSource(); |
| 128 | + // Attaching a clock should notifiy the clock |
| 129 | + timeSource.attachClock(mockedClock); |
| 130 | + verify(mockedClock).setRosTimeIsActive(false); |
| 131 | + |
| 132 | + // Setting ROS time active should notify clock |
| 133 | + timeSource.setRosTimeIsActive(true); |
| 134 | + verify(mockedClock).setRosTimeIsActive(true); |
| 135 | + } |
| 136 | + |
| 137 | + @Test(expected = IllegalArgumentException.class) |
| 138 | + public final void testAttachClockInvalidType() { |
| 139 | + TimeSource timeSource = new TimeSource(); |
| 140 | + timeSource.attachClock(mockedClock); |
| 141 | + } |
| 142 | + |
| 143 | + @Test |
| 144 | + public final void testDetachClock() { |
| 145 | + when(mockedClock.getClockType()).thenReturn(ClockType.ROS_TIME); |
| 146 | + |
| 147 | + TimeSource timeSource = new TimeSource(); |
| 148 | + timeSource.attachClock(mockedClock); |
| 149 | + timeSource.detachClock(mockedClock); |
| 150 | + |
| 151 | + // Setting ROS time active should not notify a detached clock |
| 152 | + timeSource.setRosTimeIsActive(true); |
| 153 | + verify(mockedClock, never()).setRosTimeIsActive(true); |
| 154 | + } |
| 155 | + |
| 156 | + @Test |
| 157 | + public final void testSetRosTimeIsActiveNoNode() { |
| 158 | + TimeSource timeSource = new TimeSource(); |
| 159 | + timeSource.setRosTimeIsActive(false); |
| 160 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 161 | + timeSource.setRosTimeIsActive(true); |
| 162 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 163 | + } |
| 164 | + |
| 165 | + @Test |
| 166 | + public final void testSetRosTimeIsActiveWithNode() { |
| 167 | + when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false)); |
| 168 | + when(mockedNode.createSubscription(eq(rosgraph_msgs.msg.Clock.class), anyString(), any(Consumer.class))) |
| 169 | + .thenReturn(mockSubscription); |
| 170 | + |
| 171 | + TimeSource timeSource = new TimeSource(mockedNode); |
| 172 | + timeSource.setRosTimeIsActive(false); |
| 173 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 174 | + timeSource.setRosTimeIsActive(true); |
| 175 | + assertTrue(timeSource.getRosTimeIsActive()); |
| 176 | + // Expect subscription for the "/clock" topic when set active |
| 177 | + verify(mockedNode).createSubscription(eq(rosgraph_msgs.msg.Clock.class), eq("/clock"), any(Consumer.class)); |
| 178 | + timeSource.setRosTimeIsActive(false); |
| 179 | + assertFalse(timeSource.getRosTimeIsActive()); |
| 180 | + // Expect subscription removed when set not active |
| 181 | + verify(mockedNode).removeSubscription(any(Subscription.class)); |
| 182 | + } |
| 183 | +} |
0 commit comments