NodeHandle.java
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 // author: Jason Wolfe
00036 
00037 package ros;
00038 
00039 import java.util.Collection;
00040 import java.util.HashMap;
00041 import java.util.Map;
00042 
00043 import ros.communication.*;
00044 
00045 public abstract class NodeHandle {
00046         
00047         // Node and master info
00048         public abstract NodeHandle copy();
00049         public abstract String getNamespace();
00050         public abstract String resolveName(String name);
00051         public abstract String getName();
00052         public abstract boolean isValid();
00053         public abstract void shutdown();
00054   public abstract boolean ok();
00055 
00056         public abstract boolean checkMaster();
00057         public abstract String getMasterHost();
00058         public abstract int getMasterPort();
00059         public abstract void setMasterRetryTimeout(int ms);
00060 
00061         
00062         // Getting and setting parameters
00063     // TODO: support for XmlRpc values
00064         
00065         public abstract boolean hasParam(String param);
00066 
00067         public abstract boolean getBooleanParam(String param, boolean useCache) throws RosException;
00068         public abstract int     getIntParam(String param, boolean useCache)     throws RosException;
00069         public abstract double  getDoubleParam(String param, boolean useCache)  throws RosException;
00070         public abstract String  getStringParam(String param, boolean useCache)  throws RosException;
00071         
00072         public boolean getBooleanParam(String param)  throws RosException {return getBooleanParam(param, false); }
00073         public int     getIntParam(String param)      throws RosException {return getIntParam(param, false); }
00074         public double  getDoubleParam(String param)   throws RosException {return getDoubleParam(param, false); }
00075         public String  getStringParam(String param)   throws RosException {return getStringParam(param, false); }
00076 
00077         public abstract void setParam(String param, boolean value) throws RosException;
00078         public abstract void setParam(String param, int     value);
00079         public abstract void setParam(String param, double  value);
00080         public abstract void setParam(String param, String  value);
00081 
00082         
00083         // Listing publications and subscriptions
00084 
00085         public abstract Collection<Topic> getTopics();
00086         public abstract Collection<String>  getAdvertisedTopics();
00087         public abstract Collection<String>  getSubscribedTopics();
00088         
00089 
00090         
00091         // Managing publications and subscriptions
00092         // TODO: support for custom callback queues or subscription callbacks
00093         
00094         public abstract <M extends Message> Publisher<M> advertise(String newTopic, M messageTemplate, int queueSize, boolean latch) throws RosException;
00095         
00096         public <M extends Message> Publisher<M> advertise(String newTopic, M messageTemplate, int queueSize) throws RosException {
00097                 return advertise(newTopic, messageTemplate, queueSize, false);
00098         }
00099 
00100         public abstract <M extends Message> Subscriber<M> subscribe(String topic, M messageTemplate, Subscriber.Callback<M> callback, int queueSize)  throws RosException;
00101 
00102         public abstract <Q extends Message, A extends Message, S extends Service<Q, A> > ServiceServer<Q, A, S> 
00103                         advertiseService(String serviceName, S serviceTemplate, ServiceServer.Callback<Q,A> callback)  throws RosException;
00104 
00105         public abstract <Q extends Message, A extends Message, S extends Service<Q, A> > ServiceClient<Q, A, S> 
00106                                         serviceClient(String serviceName, S serviceTemplate, boolean isPersistant, Map<String, String> headerValues);
00107 
00108         public <Q extends Message, A extends Message, S extends Service<Q, A> > ServiceClient<Q, A, S> 
00109                     serviceClient(String serviceName, S serviceTemplate) {
00110                 return serviceClient(serviceName, serviceTemplate, false);
00111         }
00112 
00113         public <Q extends Message, A extends Message, S extends Service<Q, A> > ServiceClient<Q, A, S> 
00114                     serviceClient(String serviceName, S serviceTemplate, boolean isPersistant) {
00115                 return serviceClient(serviceName, serviceTemplate, isPersistant, new HashMap<String, String>());
00116         }
00117 
00118         // Convenience methods copied from Ros
00119         
00120         public abstract Time now();
00121         public abstract void spin();
00122         public abstract void spinOnce();
00123         public abstract void logDebug(String message);
00124         public abstract void logInfo(String message);
00125         public abstract void logWarn(String message);
00126         public abstract void logError(String message);
00127         public abstract void logFatal(String message);
00128 }


rosjava_jni
Author(s): Jason Wolfe (jawolfe@willowgarage.com), Nicholas Butko (nbutko@cogsci.ucsd.edu), Lorenz Moesenlechner (moesenle@in.tum.de)
autogenerated on Thu Jan 2 2014 11:07:00