rosjava & Gazebo: Problem with sim time?
Hi,
I've ran into a problem trying to connect a rosjava node to gazebo running turtlesim. If /use_sim_time is true, rosjava crashes while trying to instantiate the logger:
Loading node class: de.se.rosjava.Main
May 20, 2012 1:05:38 PM org.ros.internal.node.client.Registrar <init>
INFO: MasterXmlRpcEndpoint URI: http://localhost:11311
May 20, 2012 1:05:38 PM org.ros.internal.node.client.Registrar onPublisherAdded
INFO: Registering publisher: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</TurtleSimJava/Main, http://127.0.0.1:36053/>, TopicIdentifier</rosout>>, Topic<TopicIdentifier</rosout>, TopicDescription<rosgraph_msgs/Log, acffd30cd6b6de30f120938c17c593fb>>>>
May 20, 2012 1:05:39 PM org.ros.internal.node.client.Registrar callMaster
INFO: Response<Success, Registered [/TurtleSimJava/Main] as publisher of [/rosout], [http://ubuntu:45371/]>
May 20, 2012 1:05:39 PM org.ros.internal.node.topic.DefaultPublisher$1 onMasterRegistrationSuccess
INFO: Publisher registered: Publisher<PublisherDefinition<PublisherIdentifier<NodeIdentifier</TurtleSimJava/Main, http://127.0.0.1:36053/>, TopicIdentifier</rosout>>, Topic<TopicIdentifier</rosout>, TopicDescription<rosgraph_msgs/Log, acffd30cd6b6de30f120938c17c593fb>>>>
May 20, 2012 1:05:39 PM org.ros.internal.node.client.Registrar onSubscriberAdded
INFO: Registering subscriber: Subscriber<Topic<TopicIdentifier</clock>, TopicDescription<rosgraph_msgs/Clock, a9c97c1d230cfc112e270351a944ee47>>>
May 20, 2012 1:05:39 PM org.ros.internal.node.client.Registrar callMaster
INFO: Response<Success, Subscribed to [/clock], [http://ubuntu:52317/]>
May 20, 2012 1:05:39 PM org.ros.internal.node.topic.DefaultSubscriber$1 onMasterRegistrationSuccess
INFO: Subscriber registered: Subscriber<Topic<TopicIdentifier</clock>, TopicDescription<rosgraph_msgs/Clock, a9c97c1d230cfc112e270351a944ee47>>>
May 20, 2012 1:05:39 PM org.ros.internal.node.RosoutLogger info
INFO:
>>> Starting...
INFO: Subscriber registered: Subscriber<Topic<TopicIdentifier</clock>,
TopicDescription<rosgraph_msgs/Clock, a9c97c1d230cfc112e270351a944ee47>>>
May 20, 2012 12:43:28 PM org.ros.internal.node.RosoutLogger info
Exception in thread "pool-1-thread-9" java.lang.NullPointerException at
com.google.common.base.Preconditions.checkNotNull(Preconditions.java:187) at
org.ros.time.ClockTopicTimeProvider.getCurrentTime(ClockTopicTimeProvider.java:58) at
org.ros.internal.node.DefaultNode.getCurrentTime(DefaultNode.java:377) at
org.ros.internal.node.RosoutLogger.publish(RosoutLogger.java:58) at
org.ros.internal.node.RosoutLogger.info(RosoutLogger.java:134) at
de.se.rosjava.Main.onStart(Main.java:28) at
org.ros.internal.node.DefaultNode$5.run(DefaultNode.java:511) at
org.ros.internal.node.DefaultNode$5.run(DefaultNode.java:508) at
org.ros.concurrent.ListenerCollection$1.run(ListenerCollection.java:117) at
java.util.concurrent.ThreadPoolExecutor.runWorker(ThreadPoolExecutor.java:1110) at
java.util.concurrent.ThreadPoolExecutor$Worker.run(ThreadPoolExecutor.java:603) at
java.lang.Thread.run(Thread.java:679) ^C
If /use_sim_time is set to false, the node stops at ">>> Starting..." and seems to wait indefinitely (at least >= 10 min).
Did I miss something regarding rosjava and simulation / simulated time?
Thanks in advance!
Best regards, Andreas
P.S: The node causing this behaviour is
public class Main extends AbstractNodeMain {
Log log;
private Publisher<geometry_msgs.Twist> publisher;
@Override
public void onStart(ConnectedNode connectedNode) {
log = connectedNode.getLog();
log.info("\n>>> Starting...\n");
publisher = connectedNode.newPublisher("cmd_vel", geometry_msgs.Twist._TYPE);
publisher.publish(createForwardTwist(1.0));
}
//...
}