Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/build_and_test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
- uses: ros-tooling/setup-ros@0.0.25
with:
required-ros-distributions: foxy
- uses: ros-tooling/action-ros-ci@0.0.19
- uses: ros-tooling/action-ros-ci@master
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

with:
package-name: rosidl_generator_java rcljava_common rcljava
target-ros2-distro: foxy
Expand Down
4 changes: 4 additions & 0 deletions rcljava/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -188,6 +188,7 @@ ament_export_jars("share/${PROJECT_NAME}/java/${PROJECT_NAME}.jar")
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(std_msgs REQUIRED)
find_package(mockito_vendor REQUIRED)
ament_lint_auto_find_test_dependencies()

set(${PROJECT_NAME}_message_files
Expand Down Expand Up @@ -243,6 +244,7 @@ if(BUILD_TESTING)
# "src/test/java/org/ros2/rcljava/parameters/SyncParametersClientTest.java"
"src/test/java/org/ros2/rcljava/publisher/PublisherTest.java"
"src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java"
"src/test/java/org/ros2/rcljava/time/TimeSourceTest.java"
"src/test/java/org/ros2/rcljava/timer/TimerTest.java"
)

Expand All @@ -258,6 +260,7 @@ if(BUILD_TESTING)
# "org.ros2.rcljava.parameters.SyncParametersClientTest"
"org.ros2.rcljava.publisher.PublisherTest"
"org.ros2.rcljava.subscription.SubscriptionTest"
"org.ros2.rcljava.time.TimeSourceTest"
"org.ros2.rcljava.timer.TimerTest"
)

Expand Down Expand Up @@ -328,6 +331,7 @@ if(BUILD_TESTING)
"${builtin_interfaces_JARS}"
"${rcl_interfaces_JARS}"
"${rosgraph_msgs_JARS}"
"${mockito_vendor_JARS}"
"${_${PROJECT_NAME}_jar_file}"
"${_${PROJECT_NAME}_messages_jar_file}"
APPEND_LIBRARY_DIRS
Expand Down
1 change: 1 addition & 0 deletions rcljava/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>builtin_interfaces</test_depend>
<test_depend>mockito_vendor</test_depend>
<test_depend>rcl_interfaces</test_depend>
<test_depend>rcljava_common</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ public rcl_interfaces.msg.SetParametersResult callback(List<ParameterVariant> pa
for (ParameterVariant param : parameters) {
if (param.getName() == "use_sim_time") {
if (param.getType() == ParameterType.PARAMETER_BOOL) {
this.timeSource.rosTimeIsActive = param.asBool();
this.timeSource.setRosTimeIsActive(param.asBool());
} else {
result.setSuccessful(false);
result.setReason("'use_sim_time' parameter must be a boolean");
Expand Down
183 changes: 183 additions & 0 deletions rcljava/src/test/java/org/ros2/rcljava/time/TimeSourceTest.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,183 @@
/* Copyright 2020 Open Source Robotics Foundation, Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

package org.ros2.rcljava.time;

import static org.junit.Assert.assertTrue;
import static org.junit.Assert.assertFalse;

import org.junit.AfterClass;
import org.junit.BeforeClass;
import org.junit.Test;

import org.junit.runner.RunWith;

import static org.mockito.Mockito.*;
import org.mockito.Mock;
import org.mockito.junit.MockitoJUnitRunner;

import org.ros2.rcljava.consumers.Consumer;
import org.ros2.rcljava.RCLJava;
import org.ros2.rcljava.node.Node;
import org.ros2.rcljava.parameters.ParameterVariant;
import org.ros2.rcljava.subscription.Subscription;
import org.ros2.rcljava.time.TimeSource;

@RunWith(MockitoJUnitRunner.StrictStubs.class)
public class TimeSourceTest {
@Mock
private Node mockedNode;

@Mock
private Clock mockedClock;

@Mock
private Subscription mockSubscription;

@BeforeClass
public static void setupOnce() throws Exception {
// Just to quiet down warnings
org.apache.log4j.BasicConfigurator.configure();

RCLJava.rclJavaInit();
}

@AfterClass
public static void tearDownOnce() {
RCLJava.shutdown();
}

@Test
public final void testEmptyConstructor() {
TimeSource timeSource = new TimeSource();
assertFalse(timeSource.getRosTimeIsActive());
}

@Test
public final void testConstructorWithNode() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false));

TimeSource timeSource = new TimeSource(mockedNode);
assertFalse(timeSource.getRosTimeIsActive());
}

@Test
public final void testAttachNodeUseSimTimeFalse() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false));

TimeSource timeSource = new TimeSource();
timeSource.attachNode(mockedNode);
assertFalse(timeSource.getRosTimeIsActive());
}

@Test
public final void testAttachNodeUseSimTimeTrue() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true));

TimeSource timeSource = new TimeSource();
timeSource.attachNode(mockedNode);
assertTrue(timeSource.getRosTimeIsActive());
}

@Test
public final void testAttachNodeTwice() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true));

TimeSource timeSource = new TimeSource();
timeSource.attachNode(mockedNode);
assertTrue(timeSource.getRosTimeIsActive());

// Attach the same node again
timeSource.attachNode(mockedNode);
assertTrue(timeSource.getRosTimeIsActive());
}

@Test
public final void testDetachNode() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", true));

// Attaches node with ROS time active
TimeSource timeSource = new TimeSource(mockedNode);
assertTrue(timeSource.getRosTimeIsActive());

timeSource.detachNode();
assertFalse(timeSource.getRosTimeIsActive());

// Calling detach again shouldn't change anything
timeSource.detachNode();
assertFalse(timeSource.getRosTimeIsActive());
}

@Test
public final void testAttachClock() {
when(mockedClock.getClockType()).thenReturn(ClockType.ROS_TIME);

TimeSource timeSource = new TimeSource();
// Attaching a clock should notifiy the clock
timeSource.attachClock(mockedClock);
verify(mockedClock).setRosTimeIsActive(false);

// Setting ROS time active should notify clock
timeSource.setRosTimeIsActive(true);
verify(mockedClock).setRosTimeIsActive(true);
}

@Test(expected = IllegalArgumentException.class)
public final void testAttachClockInvalidType() {
TimeSource timeSource = new TimeSource();
timeSource.attachClock(mockedClock);
}

@Test
public final void testDetachClock() {
when(mockedClock.getClockType()).thenReturn(ClockType.ROS_TIME);

TimeSource timeSource = new TimeSource();
timeSource.attachClock(mockedClock);
timeSource.detachClock(mockedClock);

// Setting ROS time active should not notify a detached clock
timeSource.setRosTimeIsActive(true);
verify(mockedClock, never()).setRosTimeIsActive(true);
}

@Test
public final void testSetRosTimeIsActiveNoNode() {
TimeSource timeSource = new TimeSource();
timeSource.setRosTimeIsActive(false);
assertFalse(timeSource.getRosTimeIsActive());
timeSource.setRosTimeIsActive(true);
assertTrue(timeSource.getRosTimeIsActive());
}

@Test
public final void testSetRosTimeIsActiveWithNode() {
when(mockedNode.getParameter("use_sim_time")).thenReturn(new ParameterVariant("use_sim_time", false));
when(mockedNode.createSubscription(eq(rosgraph_msgs.msg.Clock.class), anyString(), any(Consumer.class)))
.thenReturn(mockSubscription);

TimeSource timeSource = new TimeSource(mockedNode);
timeSource.setRosTimeIsActive(false);
assertFalse(timeSource.getRosTimeIsActive());
timeSource.setRosTimeIsActive(true);
assertTrue(timeSource.getRosTimeIsActive());
// Expect subscription for the "/clock" topic when set active
verify(mockedNode).createSubscription(eq(rosgraph_msgs.msg.Clock.class), eq("/clock"), any(Consumer.class));
timeSource.setRosTimeIsActive(false);
assertFalse(timeSource.getRosTimeIsActive());
// Expect subscription removed when set not active
verify(mockedNode).removeSubscription(any(Subscription.class));
}
}
4 changes: 4 additions & 0 deletions ros2_java_desktop.repos
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ repositories:
type: git
url: https://github.com/ros2/unique_identifier_msgs
version: master
ros2_java/mockito_vendor:
type: git
url: https://github.com/ros2-java/mockito_vendor.git
version: main
ros2_java/ros2_java:
type: git
url: https://github.com/osrf/ros2_java.git
Expand Down