Skip to content
Snippets Groups Projects
Commit ba59add2 authored by Damon Kohler's avatar Damon Kohler
Browse files

Added NtpTimeProvider and renamed WallclockProvider to WallTimeProvider.

Improved error messages from MessageFactory.
Added fromMillis/Nanos to Duration to support NtpTimeProvider.
parent 5e6199d3
Branches
Tags
No related merge requests found
......@@ -31,6 +31,7 @@
<rosjava-pathelement groupId="com.google.guava" artifactId="org.ros.rosjava.guava" version="r07" />
<rosjava-pathelement groupId="org.jboss.netty" artifactId="netty" version="3.2.4.Final" />
<rosjava-pathelement groupId="org.apache.commons" artifactId="com.springsource.org.apache.commons.logging" version="1.1.1" />
<rosjava-pathelement groupId="commons-net" artifactId="commons-net" version="2.0" />
<rosjava-pathelement groupId="junit" artifactId="junit" version="4.8.2" scope="test" />
<rosjava-pathelement groupId="org.mockito" artifactId="mockito-all" version="1.8.5" scope="test" />
......
......@@ -16,11 +16,11 @@
package org.ros.internal.message.old_style;
import com.google.common.base.Preconditions;
import org.ros.exception.RosRuntimeException;
import org.ros.message.Message;
import com.google.common.base.Preconditions;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
......@@ -72,14 +72,12 @@ public class MessageFactory implements org.ros.message.MessageFactory {
* Get the class for a given message type.
*
* @param messageType
* The string giving "ros package"/"message name", e.g. std_msgs/Time
* the string giving "ros package"/"message name", e.g. std_msgs/Time
* @param packagePath
* Path to the package which contain messages.
*
* @return The class.
*
* path to the package which contain messages
* @return the message class
* @throws RosRuntimeException
* No class representing that name or the class is not accessible.
* no class representing that name or the class is not accessible
*/
@SuppressWarnings("unchecked")
private static Class<Message> loadMessageClass(String messageType, String packagePath) {
......@@ -88,7 +86,7 @@ public class MessageFactory implements org.ros.message.MessageFactory {
return (Class<Message>) MessageFactory.class.getClassLoader().loadClass(
packagePath + "." + messageType.replace('/', '.'));
} catch (Exception e) {
throw new RosRuntimeException(e);
throw new RosRuntimeException("Failed to load message type: \"" + messageType + "\"", e);
}
}
}
......@@ -68,7 +68,7 @@ public class DefaultNodeRunner implements NodeRunner {
*/
@Override
public void run(final NodeMain nodeMain, final NodeConfiguration nodeConfiguration) {
Preconditions.checkNotNull(nodeConfiguration.getNodeName());
Preconditions.checkNotNull(nodeConfiguration.getNodeName(), "Node name not specified.");
executor.execute(new Runnable() {
@Override
public void run() {
......
......@@ -16,13 +16,14 @@
package org.ros.node;
import org.ros.time.WallTimeProvider;
import org.ros.address.AdvertiseAddress;
import org.ros.address.AdvertiseAddressFactory;
import org.ros.address.BindAddress;
import org.ros.address.PrivateAdvertiseAddressFactory;
import org.ros.address.PublicAdvertiseAddressFactory;
import org.ros.exception.RosRuntimeException;
import org.ros.internal.time.WallclockProvider;
import org.ros.message.MessageDefinitionFactory;
import org.ros.message.MessageFactory;
import org.ros.message.MessageSerializationFactory;
......@@ -162,7 +163,7 @@ public class NodeConfiguration {
setMessageDefinitionFactory(new org.ros.internal.message.old_style.MessageDefinitionFactory());
setMessageSerializationFactory(new org.ros.internal.message.old_style.MessageSerializationFactory());
setParentResolver(NameResolver.create());
setTimeProvider(new WallclockProvider());
setTimeProvider(new WallTimeProvider());
}
/**
......@@ -450,7 +451,7 @@ public class NodeConfiguration {
/**
* Sets the {@link TimeProvider} that {@link Node}s will use. By default, the
* {@link WallclockProvider} is used.
* {@link WallTimeProvider} is used.
*
* @param timeProvider
* the {@link TimeProvider} that {@link Node}s will use
......
/*
* Copyright (C) 2011 Google 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.ros.time;
import org.apache.commons.net.ntp.NTPUDPClient;
import org.apache.commons.net.ntp.TimeInfo;
import org.ros.exception.RosRuntimeException;
import org.ros.message.Duration;
import org.ros.message.Time;
import java.io.IOException;
import java.net.InetAddress;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class NtpTimeProvider implements TimeProvider {
private final InetAddress host;
private final NTPUDPClient ntpClient;
private final WallTimeProvider wallTimeProvider;
private TimeInfo time;
public NtpTimeProvider(InetAddress host) {
this.host = host;
this.wallTimeProvider = new WallTimeProvider();
ntpClient = new NTPUDPClient();
}
public void updateTime() {
try {
time = ntpClient.getTime(host);
} catch (IOException e) {
throw new RosRuntimeException("Failed to read time from NTP server " + host.getHostName(), e);
}
time.computeDetails();
}
@Override
public Time getCurrentTime() {
Time currentTime = wallTimeProvider.getCurrentTime();
long offset = time.getOffset();
return currentTime.add(Duration.fromMillis(offset));
}
}
......@@ -14,9 +14,8 @@
* the License.
*/
package org.ros.internal.time;
package org.ros.time;
import org.ros.time.TimeProvider;
import org.ros.message.Time;
......@@ -25,7 +24,7 @@ import org.ros.message.Time;
*
* @author kwc@willowgarage.com (Ken Conley)
*/
public class WallclockProvider implements TimeProvider {
public class WallTimeProvider implements TimeProvider {
@Override
public Time getCurrentTime() {
......
/*
* Copyright (C) 2011 Google 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.ros.time;
import org.junit.Test;
import org.ros.address.InetAddressFactory;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class NtpTimeProviderTest {
@Test
public void testNtpTime() {
// TODO(damonkohler): This is only a simple sanity check.
NtpTimeProvider ntpTimeProvider =
new NtpTimeProvider(InetAddressFactory.newFromHostString("ntps1-0.cs.tu-berlin.de"));
ntpTimeProvider.updateTime();
ntpTimeProvider.getCurrentTime();
}
}
......@@ -48,6 +48,7 @@ package org.ros.message;
public class Duration implements Comparable<Duration> {
public static final Duration MAX_VALUE = new Duration(Integer.MAX_VALUE, 999999999);
public int secs;
public int nsecs;
......@@ -79,6 +80,18 @@ public class Duration implements Comparable<Duration> {
return new Duration(secs - d.secs, nsecs - d.nsecs);
}
public static Duration fromMillis(long durationInMillis) {
int secs = (int) (durationInMillis / 1000);
int nsecs = (int) (durationInMillis % 1000) * 1000000;
return new Duration(secs, nsecs);
}
public static Duration fromNano(long durationInNs) {
int secs = (int) (durationInNs / 1000000000);
int nsecs = (int) (durationInNs % 1000000000);
return new Duration(secs, nsecs);
}
public void normalize() {
while (nsecs < 0) {
nsecs += 1000000000;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment