diff --git a/src/examples/turtle.js b/src/examples/turtle.js index 27ee367..9f183bd 100644 --- a/src/examples/turtle.js +++ b/src/examples/turtle.js @@ -4,127 +4,127 @@ messages. */ -'use strict'; - -let rosnodejs = require('../index.js'); -rosnodejs.initNode('/my_node', {onTheFly: true}).then((rosNode) => { +"use strict"; +let rosnodejs = require("../index.js"); +rosnodejs.initNode("/my_node", { onTheFly: true }).then((rosNode) => { // get list of existing publishers, subscribers, and services - rosNode._node._masterApi.getSystemState("/my_node").then((data) => { + rosNode._node._primaryApi.getSystemState("/my_node").then((data) => { console.log("getSystemState, result", data, data.publishers[0]); }); // --------------------------------------------------------- // Service Call - const TeleportRelative = rosnodejs.require('turtlesim').srv.TeleportRelative; + const TeleportRelative = rosnodejs.require("turtlesim").srv.TeleportRelative; const teleport_request = new TeleportRelative.Request({ linear: -1, - angular: 0.0 + angular: 0.0, }); - let serviceClient = rosNode.serviceClient("/turtle1/teleport_relative", - "turtlesim/TeleportRelative"); - - rosNode.waitForService(serviceClient.getService(), 2000) - .then((available) => { - if (available) { - serviceClient.call(teleport_request, (resp) => { - console.log('Service response ' + JSON.stringify(resp)); - }); - } else { - console.log('Service not available'); - } - }); - + let serviceClient = rosNode.serviceClient( + "/turtle1/teleport_relative", + "turtlesim/TeleportRelative" + ); + + rosNode.waitForService(serviceClient.getService(), 2000).then((available) => { + if (available) { + serviceClient.call(teleport_request, (resp) => { + console.log("Service response " + JSON.stringify(resp)); + }); + } else { + console.log("Service not available"); + } + }); // --------------------------------------------------------- // Subscribe rosNode.subscribe( - '/turtle1/pose', - 'turtlesim/Pose', + "/turtle1/pose", + "turtlesim/Pose", (data) => { - console.log('pose', data); + console.log("pose", data); }, - {queueSize: 1, - throttleMs: 1000}); + { queueSize: 1, throttleMs: 1000 } + ); // --------------------------------------------------------- // Publish // equivalent to: // rostopic pub /turtle1/cmd_vel geometry_msgs/Twist '[1, 0, 0]' '[0, 0, 0]' - let cmd_vel = rosNode.advertise('/turtle1/cmd_vel','geometry_msgs/Twist', { + let cmd_vel = rosNode.advertise("/turtle1/cmd_vel", "geometry_msgs/Twist", { queueSize: 1, latching: true, - throttleMs: 9 + throttleMs: 9, }); - const Twist = rosnodejs.require('geometry_msgs').msg.Twist; + const Twist = rosnodejs.require("geometry_msgs").msg.Twist; const msgTwist = new Twist({ linear: { x: 1, y: 0, z: 0 }, - angular: { x: 0, y: 0, z: 1 } + angular: { x: 0, y: 0, z: 1 }, }); cmd_vel.publish(msgTwist); - // --------------------------------------------------------- // test actionlib // rosrun turtlesim turtlesim_node // rosrun turtle_actionlib shape_server // wait two seconds for previous example to complete - setTimeout(function() { - const shapeActionGoal = rosnodejs.require('turtle_actionlib').msg.ShapeActionGoal; - const ac = rosnodejs.nh.actionClient( - "/turtle_shape", - "turtle_actionlib/Shape" - ); - ac.sendGoal(new shapeActionGoal({ - goal: { - edges: 3, - radius: 1 - } - })); - setTimeout(function() { - ac.cancel(); - }, 1000); - }, 2000); + setTimeout(function () { + const shapeActionGoal = rosnodejs.require("turtle_actionlib").msg + .ShapeActionGoal; + const ac = rosnodejs.nh.actionClient( + "/turtle_shape", + "turtle_actionlib/Shape" + ); + ac.sendGoal( + new shapeActionGoal({ + goal: { + edges: 3, + radius: 1, + }, + }) + ); + setTimeout(function () { + ac.cancel(); + }, 1000); + }, 2000); // --------------------------------------------------------- // test int64 + uint64 rosNode.subscribe( - '/int64', - 'std_msgs/Int64', + "/int64", + "std_msgs/Int64", (data) => { - console.log('int64', data); + console.log("int64", data); }, - {queueSize: 1, - throttleMs: 1000}); + { queueSize: 1, throttleMs: 1000 } + ); - let int64pub = rosNode.advertise('/int64','std_msgs/Int64', { - queueSize: 1, - latching: true, - throttleMs: 9 - }); - const Int64 = rosnodejs.require('std_msgs').msg.Int64; - int64pub.publish(new Int64({ data: "429496729456789012" })); + let int64pub = rosNode.advertise("/int64", "std_msgs/Int64", { + queueSize: 1, + latching: true, + throttleMs: 9, + }); + const Int64 = rosnodejs.require("std_msgs").msg.Int64; + int64pub.publish(new Int64({ data: "429496729456789012" })); rosNode.subscribe( - '/uint64', - 'std_msgs/UInt64', + "/uint64", + "std_msgs/UInt64", (data) => { - console.log('uint64', data); + console.log("uint64", data); }, - {queueSize: 1, - throttleMs: 1000}); - - let uint64pub = rosNode.advertise('/uint64','std_msgs/UInt64', { - queueSize: 1, - latching: true, - throttleMs: 9 - }); - const UInt64 = rosnodejs.require('std_msgs').msg.UInt64; - uint64pub.publish(new UInt64({ data: "9223372036854775807" })); + { queueSize: 1, throttleMs: 1000 } + ); + let uint64pub = rosNode.advertise("/uint64", "std_msgs/UInt64", { + queueSize: 1, + latching: true, + throttleMs: 9, + }); + const UInt64 = rosnodejs.require("std_msgs").msg.UInt64; + uint64pub.publish(new UInt64({ data: "9223372036854775807" })); }); diff --git a/src/index.js b/src/index.js index 5de18b5..5b5a99a 100644 --- a/src/index.js +++ b/src/index.js @@ -19,34 +19,34 @@ //------------------------------------------------------------------ -const netUtils = require('./utils/network_utils.js'); -const msgUtils = require('./utils/message_utils.js'); -const messages = require('./utils/messageGeneration/messages.js'); -const util = require('util'); -const RosLogStream = require('./utils/log/RosLogStream.js'); -const ConsoleLogStream = require('./utils/log/ConsoleLogStream.js'); -const LogFormatter = require('./utils/log/LogFormatter.js'); -const RosNode = require('./lib/RosNode.js'); -const NodeHandle = require('./lib/NodeHandle.js'); -const Logging = require('./lib/Logging.js'); -const ActionClientInterface = require('./lib/ActionClientInterface.js'); -const Time = require('./lib/Time.js'); -const packages = require('./utils/messageGeneration/packages.js'); - -const ActionServer = require('./actions/ActionServer.js'); -const ActionClient = require('./actions/ActionClient.js'); -const ClientStates = require('./actions/ClientStates.js'); -const SimpleActionClient = require('./actions/SimpleActionClient.js'); -const SimpleActionServer = require('./actions/SimpleActionServer.js'); - -const MsgLoader = require('./utils/messageGeneration/MessageLoader.js'); -const RemapUtils = require('./utils/remapping_utils.js'); -const names = require('./lib/Names.js'); -const ThisNode = require('./lib/ThisNode.js'); +const netUtils = require("./utils/network_utils.js"); +const msgUtils = require("./utils/message_utils.js"); +const messages = require("./utils/messageGeneration/messages.js"); +const util = require("util"); +const RosLogStream = require("./utils/log/RosLogStream.js"); +const ConsoleLogStream = require("./utils/log/ConsoleLogStream.js"); +const LogFormatter = require("./utils/log/LogFormatter.js"); +const RosNode = require("./lib/RosNode.js"); +const NodeHandle = require("./lib/NodeHandle.js"); +const Logging = require("./lib/Logging.js"); +const ActionClientInterface = require("./lib/ActionClientInterface.js"); +const Time = require("./lib/Time.js"); +const packages = require("./utils/messageGeneration/packages.js"); + +const ActionServer = require("./actions/ActionServer.js"); +const ActionClient = require("./actions/ActionClient.js"); +const ClientStates = require("./actions/ClientStates.js"); +const SimpleActionClient = require("./actions/SimpleActionClient.js"); +const SimpleActionServer = require("./actions/SimpleActionServer.js"); + +const MsgLoader = require("./utils/messageGeneration/MessageLoader.js"); +const RemapUtils = require("./utils/remapping_utils.js"); +const names = require("./lib/Names.js"); +const ThisNode = require("./lib/ThisNode.js"); // will be initialized through call to initNode let log = Logging.getLogger(); -let pingMasterTimeout = null; +let pingPrimaryTimeout = null; //------------------------------------------------------------------ @@ -62,18 +62,17 @@ let Rosnodejs = { * to be used for this node * @param {function} options.logging.setLoggerLevel the function for setting the logger * level - * @param {string} options.rosMasterUri the Master URI to use for this node + * @param {string} options.rosPrimaryUri the Primary URI to use for this node * @param {number} options.timeout time in ms to wait for node to be initialized * before timing out. A negative value will retry forever. * A value of '0' will try once before stopping. @default -1 - * @return {Promise} resolved when connection to master is established + * @return {Promise} resolved when connection to primary is established */ initNode(nodeName, options) { - if (typeof nodeName !== 'string') { - throw new Error('The node name must be a string'); - } - else if (nodeName.length === 0) { - throw new Error('The node name must not be empty!'); + if (typeof nodeName !== "string") { + throw new Error("The node name must be a string"); + } else if (nodeName.length === 0) { + throw new Error("The node name must not be empty!"); } options = options || {}; @@ -85,7 +84,11 @@ let Rosnodejs = { // initialize netUtils from possible command line remappings netUtils.init(remappings); - const [resolvedName, namespace] = _resolveNodeName(nodeName, remappings, options); + const [resolvedName, namespace] = _resolveNodeName( + nodeName, + remappings, + options + ); names.init(remappings, namespace); @@ -94,30 +97,44 @@ let Rosnodejs = { return Promise.resolve(this.getNodeHandle()); } // else - return Promise.reject( Error('Unable to initialize node [' + resolvedName + '] - node [' - + ThisNode.getNodeName() + '] already exists')); + return Promise.reject( + Error( + "Unable to initialize node [" + + resolvedName + + "] - node [" + + ThisNode.getNodeName() + + "] already exists" + ) + ); } Logging.initializeNodeLogger(resolvedName, options.logging); // create the ros node. Return a promise that will - // resolve when connection to master is established + // resolve when connection to primary is established const nodeOpts = options.node || {}; - const rosMasterUri = options.rosMasterUri || remappings['__master'] || process.env.ROS_MASTER_URI;; + const rosPrimaryUri = + options.rosPrimaryUri || + remappings["__primary"] || + process.env.ROS_PRIMARY_URI; - ThisNode.node = new RosNode(resolvedName, rosMasterUri, nodeOpts); + ThisNode.node = new RosNode(resolvedName, rosPrimaryUri, nodeOpts); - return new Promise((resolve,reject)=>{ + return new Promise((resolve, reject) => { this._loadOnTheFlyMessages(options) - .then(()=>{return _checkMasterHelper(100, options.timeout);}) - .then(Logging.initializeRosOptions.bind(Logging, this, options.logging)) - .then(Time._initializeRosTime.bind(Time, this, options.notime)) - .then(() => { resolve(this.getNodeHandle()); }) - .catch((err) => { - log.error('Error during initialization: ' + err); - this.shutdown(); - reject(err); - }); + .then(() => { + return _checkPrimaryHelper(100, options.timeout); + }) + .then(Logging.initializeRosOptions.bind(Logging, this, options.logging)) + .then(Time._initializeRosTime.bind(Time, this, options.notime)) + .then(() => { + resolve(this.getNodeHandle()); + }) + .catch((err) => { + log.error("Error during initialization: " + err); + this.shutdown(); + reject(err); + }); }); }, @@ -126,7 +143,7 @@ let Rosnodejs = { }, shutdown() { - clearTimeout(pingMasterTimeout); + clearTimeout(pingPrimaryTimeout); return ThisNode.shutdown(); }, @@ -152,7 +169,7 @@ let Rosnodejs = { } }, - _loadOnTheFlyMessages({onTheFly}) { + _loadOnTheFlyMessages({ onTheFly }) { if (onTheFly) { return messages.getAll(); } @@ -160,29 +177,29 @@ let Rosnodejs = { return Promise.resolve(); }, - loadPackage(packageName, outputDir=null, verbose=false) { + loadPackage(packageName, outputDir = null, verbose = false) { const msgLoader = new MsgLoader(verbose); if (!outputDir) { outputDir = msgUtils.getTopLevelMessageDirectory(); } - return msgLoader.buildPackage(packageName, outputDir) - .then(() => { - console.log('Finished building messages!'); - }) - .catch((err) => { - console.error(err); - }); + return msgLoader + .buildPackage(packageName, outputDir) + .then(() => { + console.log("Finished building messages!"); + }) + .catch((err) => { + console.error(err); + }); }, - loadAllPackages(outputDir=null, verbose=false) { + loadAllPackages(outputDir = null, verbose = false) { const msgLoader = new MsgLoader(verbose); if (!outputDir) { outputDir = msgUtils.getTopLevelMessageDirectory(); } - return msgLoader.buildPackageTree(outputDir) - .then(() => { - console.log('Finished building messages!'); - }) + return msgLoader.buildPackageTree(outputDir).then(() => { + console.log("Finished building messages!"); + }); }, findPackage(packageName) { @@ -208,22 +225,22 @@ let Rosnodejs = { /** check that a message definition is loaded for a ros message type, e.g., geometry_msgs/Twist */ checkMessage(type) { - const parts = type.split('/'); + const parts = type.split("/"); let rtv; try { rtv = this.require(parts[0]).msg[parts[1]]; - } catch(e) {} + } catch (e) {} return rtv; }, /** check that a service definition is loaded for a ros service type, e.g., turtlesim/TeleportRelative */ checkService(type) { - const parts = type.split('/'); + const parts = type.split("/"); let rtv; try { rtv = this.require(parts[0]).srv[parts[1]]; - } catch(e) {} + } catch (e) {} return rtv; }, @@ -249,8 +266,8 @@ let Rosnodejs = { get logStreams() { return { console: ConsoleLogStream, - ros: RosLogStream - } + ros: RosLogStream, + }; }, get Time() { @@ -275,8 +292,11 @@ let Rosnodejs = { */ getActionClient(options) { return this.nh.actionClientInterface( - options.actionServer, options.type, options); - } + options.actionServer, + options.type, + options + ); + }, }; Rosnodejs.ActionServer = ActionServer; @@ -293,70 +313,80 @@ module.exports = Rosnodejs; /** * @private - * Helper function to see if the master is available and able to accept + * Helper function to see if the primary is available and able to accept * connections. * @param {number} timeout time in ms between connection attempts * @param {number} maxTimeout maximum time in ms to retry before timing out. * A negative number will make it retry forever. 0 will only make one attempt * before timing out. */ -function _checkMasterHelper(timeout=100, maxTimeout=-1) { +function _checkPrimaryHelper(timeout = 100, maxTimeout = -1) { const startTime = Date.now(); - const localHelper = (resolve,reject) => { - pingMasterTimeout = setTimeout(() => { - // also check that the slave api server is set up - if (!ThisNode.node.slaveApiSetupComplete()) { + const localHelper = (resolve, reject) => { + pingPrimaryTimeout = setTimeout(() => { + // also check that the assistant api server is set up + if (!ThisNode.node.assistantApiSetupComplete()) { if (Date.now() - startTime >= maxTimeout && maxTimeout >= 0) { - log.error(`Unable to register with master node [${ThisNode.node.getRosMasterUri()}]: unable to set up slave API Server. Stopping...`); - reject(new Error('Unable to setup slave API server.')); + log.error( + `Unable to register with primary node [${ThisNode.node.getRosPrimaryUri()}]: unable to set up assistant API Server. Stopping...` + ); + reject(new Error("Unable to setup assistant API server.")); return; } localHelper(resolve, reject); return; } - ThisNode.node.getMasterUri({ maxAttempts: 1 }) - .then(() => { - log.infoOnce(`Connected to master at ${ThisNode.node.getRosMasterUri()}!`); - pingMasterTimeout = null; - resolve(); - }) - .catch((err, resp) => { - if (Date.now() - startTime >= maxTimeout && !(maxTimeout < 0) ){ - log.error(`Timed out before registering with master node [${ThisNode.node.getRosMasterUri()}]: master may not be running yet.`); - reject(new Error('Registration with master timed out.')); - return; - } else { - log.warnThrottle(60000, `Unable to register with master node [${ThisNode.node.getRosMasterUri()}]: master may not be running yet. Will keep trying.`); - localHelper(resolve, reject); - } - }); + ThisNode.node + .getPrimaryUri({ maxAttempts: 1 }) + .then(() => { + log.infoOnce( + `Connected to primary at ${ThisNode.node.getRosPrimaryUri()}!` + ); + pingPrimaryTimeout = null; + resolve(); + }) + .catch((err, resp) => { + if (Date.now() - startTime >= maxTimeout && !(maxTimeout < 0)) { + log.error( + `Timed out before registering with primary node [${ThisNode.node.getRosPrimaryUri()}]: primary may not be running yet.` + ); + reject(new Error("Registration with primary timed out.")); + return; + } else { + log.warnThrottle( + 60000, + `Unable to register with primary node [${ThisNode.node.getRosPrimaryUri()}]: primary may not be running yet. Will keep trying.` + ); + localHelper(resolve, reject); + } + }); }, timeout); }; return new Promise((resolve, reject) => { - localHelper(resolve,reject); + localHelper(resolve, reject); }); } function _resolveNodeName(nodeName, remappings, options) { - let namespace = remappings['__ns'] || process.env.ROS_NAMESPACE || ''; + let namespace = remappings["__ns"] || process.env.ROS_NAMESPACE || ""; namespace = names.clean(namespace); - if (namespace.length === 0 || !namespace.startsWith('/')) { + if (namespace.length === 0 || !namespace.startsWith("/")) { namespace = `/${namespace}`; } names.validate(namespace, true); - nodeName = remappings['__name'] || nodeName; + nodeName = remappings["__name"] || nodeName; nodeName = names.resolve(namespace, nodeName); // only anonymize node name if they didn't remap from the command line - if (options.anonymous && !remappings['__name']) { + if (options.anonymous && !remappings["__name"]) { nodeName = _anonymizeNodeName(nodeName); } - return [nodeName, namespace] + return [nodeName, namespace]; } /** @@ -366,5 +396,5 @@ function _resolveNodeName(nodeName, remappings, options) { * @return {string} anonymized nodeName */ function _anonymizeNodeName(nodeName) { - return util.format('%s_%s_%s', nodeName, process.pid, Date.now()); + return util.format("%s_%s_%s", nodeName, process.pid, Date.now()); } diff --git a/src/lib/Logging.js b/src/lib/Logging.js index 4f7676c..8be9fa6 100644 --- a/src/lib/Logging.js +++ b/src/lib/Logging.js @@ -15,40 +15,40 @@ * limitations under the License. */ -'use strict'; -const bunyan = require('bunyan'); -const Logger = require('../utils/log/Logger.js'); -const RosLogStream = require('../utils/log/RosLogStream.js'); -const ConsoleLogStream = require('../utils/log/ConsoleLogStream.js'); -const LogFormatter = require('../utils/log/LogFormatter.js'); +"use strict"; +const bunyan = require("bunyan"); +const Logger = require("../utils/log/Logger.js"); +const RosLogStream = require("../utils/log/RosLogStream.js"); +const ConsoleLogStream = require("../utils/log/ConsoleLogStream.js"); +const LogFormatter = require("../utils/log/LogFormatter.js"); //----------------------------------------------------------------------- -const DEFAULT_LOGGER_NAME = 'ros'; +const DEFAULT_LOGGER_NAME = "ros"; const LOG_CLEANUP_INTERVAL_MS = 30000; // 30 seconds // TODO: put this in a config file somewhere const KNOWN_LOGS = [ { name: `${DEFAULT_LOGGER_NAME}.superdebug`, - level: 'fatal' + level: "fatal", }, { name: `${DEFAULT_LOGGER_NAME}.rosnodejs`, - level: 'warn' + level: "warn", }, { - name: `${DEFAULT_LOGGER_NAME}.masterapi`, - level: 'warn' + name: `${DEFAULT_LOGGER_NAME}.primaryapi`, + level: "warn", }, { name: `${DEFAULT_LOGGER_NAME}.params`, - level: 'warn' + level: "warn", }, { name: `${DEFAULT_LOGGER_NAME}.spinner`, - level: 'error' - } + level: "error", + }, ]; //----------------------------------------------------------------------- @@ -60,13 +60,15 @@ class LoggingManager { // initialize the root logger with a console stream const rootLoggerOptions = { name: DEFAULT_LOGGER_NAME, - streams: [{ - type: 'raw', - name: 'ConsoleLogStream', - stream: new ConsoleLogStream({formatter: LogFormatter}), - level: 'info' - }], - level: 'info' + streams: [ + { + type: "raw", + name: "ConsoleLogStream", + stream: new ConsoleLogStream({ formatter: LogFormatter }), + level: "info", + }, + ], + level: "info", }; this.rootLogger = new Logger(rootLoggerOptions); @@ -82,7 +84,7 @@ class LoggingManager { // through the logging services (_handleGetLoggers, _handleSetLoggerLevel) this._externalLog = { getLoggers: null, - setLoggerLevel: null + setLoggerLevel: null, }; KNOWN_LOGS.forEach((log) => { @@ -90,34 +92,36 @@ class LoggingManager { }); } - initializeNodeLogger(nodeName, options={}) { - + initializeNodeLogger(nodeName, options = {}) { // setup desired streams - if (options.hasOwnProperty('streams')) { + if (options.hasOwnProperty("streams")) { options.streams.forEach((stream) => { this.addStream(stream); }); } // set desired log level - if (options.hasOwnProperty('level')) { + if (options.hasOwnProperty("level")) { this.setLevel(options.level); } // automatically clear out expired throttled logs every so often unless specified otherwise - if (!options.hasOwnProperty('overrideLoggerCleanup')) { - this._cleanLoggersInterval = setInterval(this.clearThrottledLogs.bind(this), LOG_CLEANUP_INTERVAL_MS); + if (!options.hasOwnProperty("overrideLoggerCleanup")) { + this._cleanLoggersInterval = setInterval( + this.clearThrottledLogs.bind(this), + LOG_CLEANUP_INTERVAL_MS + ); } - if (typeof options.getLoggers === 'function') { + if (typeof options.getLoggers === "function") { this._externalLog.getLoggers = options.getLoggers; } - if (typeof options.setLoggerLevel === 'function') { + if (typeof options.setLoggerLevel === "function") { this._externalLog.setLoggerLevel = options.setLoggerLevel; } } - initializeRosOptions(rosnodejs, options={}) { + initializeRosOptions(rosnodejs, options = {}) { if (options.skipRosLogging) { return Promise.resolve(); } @@ -125,35 +129,47 @@ class LoggingManager { const nh = rosnodejs.nh; let rosLogStream; try { - const rosgraphMsgs = rosnodejs.require('rosgraph_msgs'); + const rosgraphMsgs = rosnodejs.require("rosgraph_msgs"); rosLogStream = new RosLogStream(nh, rosgraphMsgs.msg.Log); this.addStream({ - type: 'raw', - name: 'RosLogStream', - stream: rosLogStream + type: "raw", + name: "RosLogStream", + stream: rosLogStream, }); - } - catch (err) { - this.rootLogger.warn('Unable to setup ros logging stream'); + } catch (err) { + this.rootLogger.warn("Unable to setup ros logging stream"); } // try to set up logging services try { - const roscpp = rosnodejs.require('roscpp'); - const getLoggerSrv = nh.getNodeName() + '/get_loggers'; - const setLoggerSrv = nh.getNodeName() + '/set_logger_level'; - nh.advertiseService(getLoggerSrv, roscpp.srv.GetLoggers, this._handleGetLoggers.bind(this)); - nh.advertiseService(setLoggerSrv, roscpp.srv.SetLoggerLevel, this._handleSetLoggerLevel.bind(this)); - } - catch (err) { - this.rootLogger.warn('Unable to setup ros logging services'); + const roscpp = rosnodejs.require("roscpp"); + const getLoggerSrv = nh.getNodeName() + "/get_loggers"; + const setLoggerSrv = nh.getNodeName() + "/set_logger_level"; + nh.advertiseService( + getLoggerSrv, + roscpp.srv.GetLoggers, + this._handleGetLoggers.bind(this) + ); + nh.advertiseService( + setLoggerSrv, + roscpp.srv.SetLoggerLevel, + this._handleSetLoggerLevel.bind(this) + ); + } catch (err) { + this.rootLogger.warn("Unable to setup ros logging services"); } - if (rosLogStream && options.waitOnRosOut !== undefined && options.waitOnRosOut) { - this.rootLogger.debug('Waiting for /rosout connection before resolving node initialization...'); - return new Promise((resolve,reject) => { - rosLogStream.getPub().on('connection', () => { - this.rootLogger.debug('Got connection to /rosout !'); + if ( + rosLogStream && + options.waitOnRosOut !== undefined && + options.waitOnRosOut + ) { + this.rootLogger.debug( + "Waiting for /rosout connection before resolving node initialization..." + ); + return new Promise((resolve, reject) => { + rosLogStream.getPub().on("connection", () => { + this.rootLogger.debug("Got connection to /rosout !"); resolve(); }); }); @@ -162,8 +178,8 @@ class LoggingManager { } generateLogger(options) { - if (!options.hasOwnProperty('name')) { - throw new Error('Unable to generate logger without name'); + if (!options.hasOwnProperty("name")) { + throw new Error("Unable to generate logger without name"); } const loggerName = options.name; @@ -173,7 +189,11 @@ class LoggingManager { } // else // generate a child logger from root - let newLogger = this._createChildLogger(loggerName, this.rootLogger, options); + let newLogger = this._createChildLogger( + loggerName, + this.rootLogger, + options + ); // stash the logger and return it this.loggerMap[loggerName] = newLogger; @@ -183,8 +203,7 @@ class LoggingManager { getLogger(loggerName, options) { if (!loggerName || loggerName === this.rootLogger.getName()) { return this.rootLogger; - } - else if (!this.hasLogger(loggerName)) { + } else if (!this.hasLogger(loggerName)) { options = options || {}; options.name = loggerName; return this.generateLogger(options); @@ -251,7 +270,7 @@ class LoggingManager { this._forEachLogger((logger) => { resp.loggers.push({ name: logger.getName(), - level: bunyan.nameFromLevel[logger.getLevel()] + level: bunyan.nameFromLevel[logger.getLevel()], }); }, true); @@ -277,11 +296,11 @@ class LoggingManager { } _bindNodeLoggerMethods(logger) { - const rawMethods = ['trace', 'debug', 'info', 'warn', 'error', 'fatal']; + const rawMethods = ["trace", "debug", "info", "warn", "error", "fatal"]; let methods = []; rawMethods.forEach((method) => methods.push(method)); - rawMethods.forEach((method) => methods.push(method + 'Throttle')); - rawMethods.forEach((method) => methods.push(method + 'Once')); + rawMethods.forEach((method) => methods.push(method + "Throttle")); + rawMethods.forEach((method) => methods.push(method + "Once")); methods.forEach((method) => { this[method] = logger[method].bind(logger); }); @@ -292,7 +311,7 @@ class LoggingManager { perLoggerCallback(this.rootLogger); } Object.keys(this.loggerMap).forEach((loggerName) => { - perLoggerCallback(this.loggerMap[loggerName]) + perLoggerCallback(this.loggerMap[loggerName]); }); } @@ -302,12 +321,12 @@ class LoggingManager { options.scope = childLoggerName; // create logger - const childLogger = parentLogger.child(options); + const childLogger = parentLogger.child(options); // cache in map this.loggerMap[childLoggerName] = childLogger; return childLogger; - }; + } } module.exports = new LoggingManager(); diff --git a/src/lib/MasterApiClient.js b/src/lib/MasterApiClient.js index 6a56f33..99c25c9 100644 --- a/src/lib/MasterApiClient.js +++ b/src/lib/MasterApiClient.js @@ -17,20 +17,22 @@ "use strict"; -let xmlrpc = require('xmlrpc'); -let networkUtils = require('../utils/network_utils.js'); -let Logging = require('./Logging.js'); -const XmlrpcClient = require('../utils/XmlrpcClient.js'); +let xmlrpc = require("xmlrpc"); +let networkUtils = require("../utils/network_utils.js"); +let Logging = require("./Logging.js"); +const XmlrpcClient = require("../utils/XmlrpcClient.js"); //----------------------------------------------------------------------- -class MasterApiClient { - - constructor(rosMasterUri, logName) { - this._log = Logging.getLogger(Logging.DEFAULT_LOGGER_NAME + '.masterapi'); - this._log.info('Connecting to ROS Master at ' + rosMasterUri); - this._xmlrpcClient = new XmlrpcClient(networkUtils.getAddressAndPortFromUri(rosMasterUri), this._log); - }; +class PrimaryApiClient { + constructor(rosPrimaryUri, logName) { + this._log = Logging.getLogger(Logging.DEFAULT_LOGGER_NAME + ".primaryapi"); + this._log.info("Connecting to ROS Primary at " + rosPrimaryUri); + this._xmlrpcClient = new XmlrpcClient( + networkUtils.getAddressAndPortFromUri(rosPrimaryUri), + this._log + ); + } getXmlrpcClient() { return this._xmlrpcClient; @@ -41,117 +43,98 @@ class MasterApiClient { } registerService(callerId, service, serviceUri, uri, options) { - let data = [ - callerId, - service, - serviceUri, - uri - ]; + let data = [callerId, service, serviceUri, uri]; return new Promise((resolve, reject) => { - this._call('registerService', data, resolve, reject, options); + this._call("registerService", data, resolve, reject, options); }); } unregisterService(callerId, service, serviceUri, options) { - let data = [ - callerId, - service, - serviceUri - ]; + let data = [callerId, service, serviceUri]; return new Promise((resolve, reject) => { - this._call('unregisterService', data, resolve, reject, options); + this._call("unregisterService", data, resolve, reject, options); }); } registerSubscriber(callerId, topic, topicType, uri, options) { - let data = [ - callerId, - topic, - topicType, - uri - ]; + let data = [callerId, topic, topicType, uri]; return new Promise((resolve, reject) => { - this._call('registerSubscriber', data, resolve, reject, options); + this._call("registerSubscriber", data, resolve, reject, options); }); } unregisterSubscriber(callerId, topic, uri, options) { - let data = [ - callerId, - topic, - uri - ]; + let data = [callerId, topic, uri]; return new Promise((resolve, reject) => { - this._call('unregisterSubscriber', data, resolve, reject, options); + this._call("unregisterSubscriber", data, resolve, reject, options); }); } registerPublisher(callerId, topic, topicType, uri, options) { - let data = [ - callerId, - topic, - topicType, - uri - ]; + let data = [callerId, topic, topicType, uri]; return new Promise((resolve, reject) => { - this._call('registerPublisher', data, resolve, reject, options); + this._call("registerPublisher", data, resolve, reject, options); }); } unregisterPublisher(callerId, topic, uri, options) { - let data = [ - callerId, - topic, - uri - ]; + let data = [callerId, topic, uri]; return new Promise((resolve, reject) => { - this._call('unregisterPublisher', data, resolve, reject, options); + this._call("unregisterPublisher", data, resolve, reject, options); }); } lookupNode(callerId, nodeName, options) { let data = [callerId, nodeName]; return new Promise((resolve, reject) => { - this._call('lookupNode', data, resolve, reject, options); + this._call("lookupNode", data, resolve, reject, options); }); } getPublishedTopics(callerId, subgraph, options) { let data = [callerId, subgraph]; - return new Promise((resolve,reject)=>{ + return new Promise((resolve, reject) => { this._call( - 'getPublishedTopics', - data, - function(data) { + "getPublishedTopics", + data, + function (data) { return resolve({ - topics: data[2].map((topic) => { return { - name: topic[0], type: topic[1] - }}) - }) - }, + topics: data[2].map((topic) => { + return { + name: topic[0], + type: topic[1], + }; + }), + }); + }, reject, - options); - }) + options + ); + }); } getTopicTypes(callerId, options) { let data = [callerId]; - return new Promise((resolve,reject)=>{ + return new Promise((resolve, reject) => { this._call( - 'getTopicTypes', - data, - function(data) { + "getTopicTypes", + data, + function (data) { return resolve({ - topics: data[2].map((topic) => { return { - name: topic[0], type: topic[1] - }}) - }) - }, + topics: data[2].map((topic) => { + return { + name: topic[0], + type: topic[1], + }; + }), + }); + }, reject, - options); - }) + options + ); + }); } /** return an object containing all current publishers (by topic), @@ -165,13 +148,13 @@ class MasterApiClient { let data = [callerId]; return new Promise((resolve, reject) => { this._call( - 'getSystemState', + "getSystemState", data, - function(data) { + function (data) { return resolve({ publishers: data[2][0].reduce(toObject, {}), subscribers: data[2][1].reduce(toObject, {}), - services: data[2][2].reduce(toObject, {}) + services: data[2][2].reduce(toObject, {}), }); }, reject, @@ -183,18 +166,18 @@ class MasterApiClient { getUri(callerId, options) { let data = [callerId]; return new Promise((resolve, reject) => { - this._call('getUri', data, resolve, reject, options); + this._call("getUri", data, resolve, reject, options); }); } lookupService(callerId, service, options) { let data = [callerId, service]; return new Promise((resolve, reject) => { - this._call('lookupService', data, resolve, reject, options); + this._call("lookupService", data, resolve, reject, options); }); } -}; +} //----------------------------------------------------------------------- -module.exports = MasterApiClient; +module.exports = PrimaryApiClient; diff --git a/src/lib/NodeHandle.js b/src/lib/NodeHandle.js index dc43493..73b6c52 100644 --- a/src/lib/NodeHandle.js +++ b/src/lib/NodeHandle.js @@ -15,13 +15,13 @@ * limitations under the License. */ -'use strict'; +"use strict"; -let RosNode = require('./RosNode.js'); -const messageUtils = require('../utils/message_utils.js'); -const names = require('./Names.js'); -const ActionClientInterface = require('./ActionClientInterface.js'); -const ActionServerInterface = require('./ActionServerInterface.js'); +let RosNode = require("./RosNode.js"); +const messageUtils = require("../utils/message_utils.js"); +const names = require("./Names.js"); +const ActionClientInterface = require("./ActionClientInterface.js"); +const ActionServerInterface = require("./ActionServerInterface.js"); /** * Handle class for nodes created with rosnodejs @@ -29,19 +29,19 @@ const ActionServerInterface = require('./ActionServerInterface.js'); * @param namespace {string} namespace of node. @default null */ class NodeHandle { - constructor(node, namespace=null) { + constructor(node, namespace = null) { this._node = node; - this._namespace = ''; + this._namespace = ""; this.setNamespace(namespace); } setNamespace(namespace) { - if (typeof namespace !== 'string') { - namespace = ''; + if (typeof namespace !== "string") { + namespace = ""; } - if (namespace.startsWith('~')) { + if (namespace.startsWith("~")) { namespace = names.resolve(namespace); } @@ -56,9 +56,9 @@ class NodeHandle { return this._node && this._node.isShutdown(); } -//------------------------------------------------------------------ -// Pubs, Subs, Services -//------------------------------------------------------------------ + //------------------------------------------------------------------ + // Pubs, Subs, Services + //------------------------------------------------------------------ /** * Creates a ros publisher with the provided options * @param topic {string} @@ -70,27 +70,27 @@ class NodeHandle { * @param [options.throttleMs] {number} milliseconds to throttle when publishing * @return {Publisher} */ - advertise(topic, type, options={}) { + advertise(topic, type, options = {}) { if (!topic) { throw new Error(`Unable to advertise unnamed topic - got ${topic}`); } if (!type) { - throw new Error(`Unable to advertise topic ${topic} without type - got ${type}`); + throw new Error( + `Unable to advertise topic ${topic} without type - got ${type}` + ); } try { options.topic = this.resolveName(topic); - if (typeof type === 'string' || type instanceof String) { + if (typeof type === "string" || type instanceof String) { options.type = type; options.typeClass = messageUtils.getHandlerForMsgType(type, true); - } - else { + } else { options.typeClass = type; options.type = type.datatype(); } return this._node.advertise(options); - } - catch (err) { + } catch (err) { this._node._log.error(`Exception trying to advertise topic ${topic}`); throw err; } @@ -106,27 +106,27 @@ class NodeHandle { * @param [options.throttleMs] {number} milliseconds to throttle when subscribing * @return {Subscriber} */ - subscribe(topic, type, callback, options={}) { + subscribe(topic, type, callback, options = {}) { if (!topic) { throw new Error(`Unable to subscribe to unnamed topic - got ${topic}`); } if (!type) { - throw new Error(`Unable to subscribe to topic ${topic} without type - got ${type}`); + throw new Error( + `Unable to subscribe to topic ${topic} without type - got ${type}` + ); } try { options.topic = this.resolveName(topic); - if (typeof type === 'string' || type instanceof String) { + if (typeof type === "string" || type instanceof String) { options.type = type; options.typeClass = messageUtils.getHandlerForMsgType(type, true); - } - else { + } else { options.typeClass = type; options.type = type.datatype(); } return this._node.subscribe(options, callback); - } - catch (err) { + } catch (err) { this._node._log.error(`Exception trying to subscribe to topic ${topic}`); throw err; } @@ -149,23 +149,23 @@ class NodeHandle { throw new Error(`Unable to advertise unnamed service - got ${service}`); } if (!type) { - throw new Error(`Unable to advertise service ${service} without type - got ${type}`); + throw new Error( + `Unable to advertise service ${service} without type - got ${type}` + ); } try { let options = { service: this.resolveName(service) }; - if (typeof type === 'string' || type instanceof String) { + if (typeof type === "string" || type instanceof String) { options.type = type; options.typeClass = messageUtils.getHandlerForSrvType(type, true); - } - else { + } else { options.typeClass = type; options.type = type.datatype(); } return this._node.advertiseService(options, callback); - } - catch (err) { + } catch (err) { this._node._log.error(`Exception trying to advertise service ${service}`); throw err; } @@ -178,28 +178,32 @@ class NodeHandle { * @param options {Object} extra options to pass to service client * @return {ServiceClient} */ - serviceClient(service, type, options={}) { + serviceClient(service, type, options = {}) { if (!service) { - throw new Error(`Unable to create unnamed service client - got ${service}`); + throw new Error( + `Unable to create unnamed service client - got ${service}` + ); } if (!type) { - throw new Error(`Unable to create service client ${service} without type - got ${type}`); + throw new Error( + `Unable to create service client ${service} without type - got ${type}` + ); } options.service = this.resolveName(service); try { - if (typeof type === 'string' || type instanceof String) { + if (typeof type === "string" || type instanceof String) { options.type = type; options.typeClass = messageUtils.getHandlerForSrvType(type, true); - } - else { + } else { options.typeClass = type; options.type = type.datatype(); } return this._node.serviceClient(options); - } - catch (err) { - this._node._log.error(`Exception trying to create service client ${service}`); + } catch (err) { + this._node._log.error( + `Exception trying to create service client ${service}` + ); throw err; } } @@ -221,41 +225,51 @@ class NodeHandle { */ actionClientInterface(actionServer, type, options = {}) { if (!actionServer) { - throw new Error(`Unable to create action client to unspecified server - [${actionServer}]`); - } - else if (!type) { - throw new Error(`Unable to create action client ${actionServer} without type - got ${type}`); + throw new Error( + `Unable to create action client to unspecified server - [${actionServer}]` + ); + } else if (!type) { + throw new Error( + `Unable to create action client ${actionServer} without type - got ${type}` + ); } // don't namespace action client - topics will be resolved by // advertising through this NodeHandle - return new ActionClientInterface(Object.assign({}, options, { - actionServer, - type, - nh: this - })); + return new ActionClientInterface( + Object.assign({}, options, { + actionServer, + type, + nh: this, + }) + ); } - actionServerInterface(actionServer, type, options={}) { + actionServerInterface(actionServer, type, options = {}) { if (!actionServer) { - throw new Error(`Unable to create unspecified action server [${actionServer}]`); - } - else if (!type) { - throw new Error(`Unable to create action server ${actionServer} without type - got ${type}`); + throw new Error( + `Unable to create unspecified action server [${actionServer}]` + ); + } else if (!type) { + throw new Error( + `Unable to create action server ${actionServer} without type - got ${type}` + ); } // don't namespace action server - topics will be resolved by // advertising through this NodeHandle - return new ActionServerInterface(Object.assign({}, options, { - actionServer, - type, - nh: this - })); + return new ActionServerInterface( + Object.assign({}, options, { + actionServer, + type, + nh: this, + }) + ); } /** * Stop receiving callbacks for this topic - * Unregisters subscriber from master + * Unregisters subscriber from primary * @param topic {string} topic to unsubscribe from */ unsubscribe(topic) { @@ -264,7 +278,7 @@ class NodeHandle { /** * Stops publishing on this topic - * Unregisters publisher from master + * Unregisters publisher from primary * @param topic {string} topic to unadvertise */ unadvertise(topic) { @@ -272,7 +286,7 @@ class NodeHandle { } /** - * Unregister service from master + * Unregister service from primary * @param service {string} service to unadvertise */ unadvertiseService(service) { @@ -280,7 +294,7 @@ class NodeHandle { } /** - * Polls master for service + * Polls primary for service * @param service {string} name of service * @param [timeout] {number} give up after some time * @return {Promise} resolved when service exists or timeout occurs. Returns true/false for service existence @@ -289,14 +303,15 @@ class NodeHandle { service = this.resolveName(service); let _waitForService = (callback, timeout) => { - setTimeout( () => { - this._node.lookupService(service) - .then((resp) => { - callback(true); - }) - .catch((err, resp) => { - _waitForService(callback, 500); - }) + setTimeout(() => { + this._node + .lookupService(service) + .then((resp) => { + callback(true); + }) + .catch((err, resp) => { + _waitForService(callback, 500); + }); }, timeout); }; @@ -304,7 +319,7 @@ class NodeHandle { _waitForService(resolve, 0); }); - if (typeof timeout === 'number') { + if (typeof timeout === "number") { let timeoutPromise = new Promise((resolve, reject) => { setTimeout(resolve.bind(null, false), timeout); }); @@ -315,8 +330,8 @@ class NodeHandle { return waitPromise; } - getMasterUri() { - return this._node.getMasterUri(); + getPrimaryUri() { + return this._node.getPrimaryUri(); } /** @@ -324,7 +339,6 @@ class NodeHandle { * @property {{name: string, type: string}[]} topics Array of topics */ - /** * Get list of topics that can be subscribed to. This does not return * topics that have no publishers. @@ -335,7 +349,7 @@ class NodeHandle { * Will return all names if no subgraph is given. * @return {Promise.} */ - getPublishedTopics(subgraph="") { + getPublishedTopics(subgraph = "") { return this._node.getPublishedTopics(subgraph); } @@ -348,7 +362,6 @@ class NodeHandle { return this._node.getTopicTypes(); } - /** * @typedef {Object} SystemState * @property {{...string:Array.}} publishers An object with topic names as keys and @@ -365,13 +378,13 @@ class NodeHandle { * * @return {Promise.} */ - getSystemState(){ + getSystemState() { return this._node.getSystemState(); } -//------------------------------------------------------------------ -// Param Interface -//------------------------------------------------------------------ + //------------------------------------------------------------------ + // Param Interface + //------------------------------------------------------------------ deleteParam(key) { return this._node.deleteParam(this.resolveName(key)); } @@ -401,20 +414,17 @@ class NodeHandle { return this._namespace; } - if (name.startsWith('~')) { - throw new Error('Using ~ names with NodeHandle methods is not allowed'); - } - else if (!name.startsWith('/') && this._namespace.length > 0) { + if (name.startsWith("~")) { + throw new Error("Using ~ names with NodeHandle methods is not allowed"); + } else if (!name.startsWith("/") && this._namespace.length > 0) { name = names.append(this._namespace, name); - } - else { + } else { name = names.clean(name); } if (remap) { return this._remapName(name); - } - else { + } else { return names.resolve(name, false); } } diff --git a/src/lib/Publisher.js b/src/lib/Publisher.js index 2dd3040..21ff6c4 100644 --- a/src/lib/Publisher.js +++ b/src/lib/Publisher.js @@ -17,9 +17,9 @@ "use strict"; -const EventEmitter = require('events'); -const Ultron = require('ultron'); -const {rebroadcast} = require('../utils/event_utils.js'); +const EventEmitter = require("events"); +const Ultron = require("ultron"); +const { rebroadcast } = require("../utils/event_utils.js"); /** * @class Publisher @@ -37,10 +37,10 @@ class Publisher extends EventEmitter { this._topic = impl.getTopic(); this._type = impl.getType(); - rebroadcast('registered', this._ultron, this); - rebroadcast('connection', this._ultron, this); - rebroadcast('disconnect', this._ultron, this); - rebroadcast('error', this._ultron, this); + rebroadcast("registered", this._ultron, this); + rebroadcast("connection", this._ultron, this); + rebroadcast("disconnect", this._ultron, this); + rebroadcast("error", this._ultron, this); } /** @@ -86,13 +86,13 @@ class Publisher extends EventEmitter { /** * Shuts down this publisher. If this is the last publisher on this topic - * for this node, closes the publisher and unregisters the topic from Master + * for this node, closes the publisher and unregisters the topic from Primary * @returns {Promise} */ shutdown() { - const topic= this.getTopic(); + const topic = this.getTopic(); if (this._impl) { - const impl = this._impl + const impl = this._impl; this._impl = null; this._ultron.destroy(); this._ultron = null; diff --git a/src/lib/RosNode.js b/src/lib/RosNode.js index 0738e48..b976f27 100644 --- a/src/lib/RosNode.js +++ b/src/lib/RosNode.js @@ -15,48 +15,47 @@ * limitations under the License. */ -"use strict" - -let net = require('net'); -let xmlrpc = require('xmlrpc'); -let MasterApiClient = require('./MasterApiClient.js'); -let SlaveApiClient = require('./SlaveApiClient.js'); -let ParamServerApiClient = require('./ParamServerApiClient.js'); -let Subscriber = require('./Subscriber.js'); -let Publisher = require('./Publisher.js'); -const PublisherImpl = require('./impl/PublisherImpl.js'); -const SubscriberImpl = require('./impl/SubscriberImpl.js'); -let ServiceClient = require('./ServiceClient.js'); -let ServiceServer = require('./ServiceServer.js'); -const GlobalSpinner = require('../utils/spinners/GlobalSpinner.js'); -let NetworkUtils = require('../utils/network_utils.js'); -let messageUtils = require('../utils/message_utils.js'); -let tcprosUtils = require('../utils/tcpros_utils.js'); -let SerializationUtils = require('../utils/serialization_utils.js'); +"use strict"; + +let net = require("net"); +let xmlrpc = require("xmlrpc"); +let PrimaryApiClient = require("./PrimaryApiClient.js"); +let AssitantApiClient = require("./AssitantApiClient.js"); +let ParamServerApiClient = require("./ParamServerApiClient.js"); +let Subscriber = require("./Subscriber.js"); +let Publisher = require("./Publisher.js"); +const PublisherImpl = require("./impl/PublisherImpl.js"); +const SubscriberImpl = require("./impl/SubscriberImpl.js"); +let ServiceClient = require("./ServiceClient.js"); +let ServiceServer = require("./ServiceServer.js"); +const GlobalSpinner = require("../utils/spinners/GlobalSpinner.js"); +let NetworkUtils = require("../utils/network_utils.js"); +let messageUtils = require("../utils/message_utils.js"); +let tcprosUtils = require("../utils/tcpros_utils.js"); +let SerializationUtils = require("../utils/serialization_utils.js"); let DeserializeStream = SerializationUtils.DeserializeStream; let Deserialize = SerializationUtils.Deserialize; let Serialize = SerializationUtils.Serialize; -let EventEmitter = require('events'); -let Logging = require('./Logging.js'); +let EventEmitter = require("events"); +let Logging = require("./Logging.js"); /** - * Create a ros node interface to the master + * Create a ros node interface to the primary * @param name {string} name of the node - * @param rosMaster {string} full uri of ros maxter (http://localhost:11311) + * @param rosPrimary {string} full uri of ros maxter (http://localhost:11311) */ class RosNode extends EventEmitter { - - constructor(nodeName, rosMaster, options={}) { + constructor(nodeName, rosPrimary, options = {}) { super(); - // ActionServers are listening to the shutdown event right now, each of which will add - // listeners to RosNode for shutdown + // ActionServers are listening to the shutdown event right now, each of which will add + // listeners to RosNode for shutdown this.setMaxListeners(0); - this._log = Logging.getLogger('ros.rosnodejs'); - this._debugLog = Logging.getLogger('ros.superdebug'); + this._log = Logging.getLogger("ros.rosnodejs"); + this._debugLog = Logging.getLogger("ros.superdebug"); - this._slaveApiServer = null; + this._assistantApiServer = null; this._xmlrpcPort = null; this._tcprosServer = null; @@ -64,12 +63,14 @@ class RosNode extends EventEmitter { this._nodeName = nodeName; - this._rosMasterAddress = rosMaster; + this._rosPrimaryAddress = rosPrimary; - this._masterApi = new MasterApiClient(this._rosMasterAddress); + this._primaryApi = new PrimaryApiClient(this._rosPrimaryAddress); - // the param server is hosted on the master -- share its xmlrpc client - this._paramServerApi = new ParamServerApiClient(this._masterApi.getXmlrpcClient()); + // the param server is hosted on the primary -- share its xmlrpc client + this._paramServerApi = new ParamServerApiClient( + this._primaryApi.getXmlrpcClient() + ); this._publishers = {}; @@ -77,8 +78,9 @@ class RosNode extends EventEmitter { this._services = {}; - this._setupTcprosServer(options.tcprosPort) - .then(this._setupSlaveApi.bind(this, options.xmlrpcPort)); + this._setupTcprosServer(options.tcprosPort).then( + this._setupAssistantApi.bind(this, options.xmlrpcPort) + ); this._setupExitHandler(); @@ -95,8 +97,8 @@ class RosNode extends EventEmitter { return this._spinner; } - getRosMasterUri() { - return this._rosMasterAddress; + getRosPrimaryUri() { + return this._rosPrimaryAddress; } advertise(options) { @@ -119,8 +121,8 @@ class RosNode extends EventEmitter { } const sub = new Subscriber(subImpl); - if (callback && typeof callback === 'function') { - sub.on('message', callback); + if (callback && typeof callback === "function") { + sub.on("message", callback); } return sub; @@ -130,7 +132,10 @@ class RosNode extends EventEmitter { let service = options.service; let serv = this._services[service]; if (serv) { - this._log.warn('Tried to advertise a service that is already advertised in this node [%s]', service); + this._log.warn( + "Tried to advertise a service that is already advertised in this node [%s]", + service + ); return; } // else @@ -146,7 +151,7 @@ class RosNode extends EventEmitter { unsubscribe(topic, options) { const sub = this._subscribers[topic]; if (sub) { - this._debugLog.info('Unsubscribing from topic %s', topic); + this._debugLog.info("Unsubscribing from topic %s", topic); delete this._subscribers[topic]; sub.shutdown(); return this.unregisterSubscriber(topic, options); @@ -156,7 +161,7 @@ class RosNode extends EventEmitter { unadvertise(topic, options) { const pub = this._publishers[topic]; if (pub) { - this._debugLog.info('Unadvertising topic %s', topic); + this._debugLog.info("Unadvertising topic %s", topic); delete this._publishers[topic]; pub.shutdown(); return this.unregisterPublisher(topic, options); @@ -166,7 +171,7 @@ class RosNode extends EventEmitter { unadvertiseService(service, options) { const server = this._services[service]; if (server) { - this._debugLog.info('Unadvertising service %s', service); + this._debugLog.info("Unadvertising service %s", service); server.disconnect(); delete this._services[service]; return this.unregisterService(service, server.getServiceUri(), options); @@ -189,14 +194,13 @@ class RosNode extends EventEmitter { return this._nodeName; } -//------------------------------------------------------------------ -// Master API -//------------------------------------------------------------------ + //------------------------------------------------------------------ + // Primary API + //------------------------------------------------------------------ registerService(service, options) { - return this._whenReady() - .then(() => { - return this._masterApi.registerService( + return this._whenReady().then(() => { + return this._primaryApi.registerService( this._nodeName, service, NetworkUtils.formatServiceUri(this._tcprosPort), @@ -207,9 +211,8 @@ class RosNode extends EventEmitter { } unregisterService(service, options) { - return this._whenReady() - .then(() => { - return this._masterApi.unregisterService( + return this._whenReady().then(() => { + return this._primaryApi.unregisterService( this._nodeName, service, NetworkUtils.formatServiceUri(this._tcprosPort), @@ -219,9 +222,8 @@ class RosNode extends EventEmitter { } registerSubscriber(topic, topicType, options) { - return this._whenReady() - .then(() => { - return this._masterApi.registerSubscriber( + return this._whenReady().then(() => { + return this._primaryApi.registerSubscriber( this._nodeName, topic, topicType, @@ -232,9 +234,8 @@ class RosNode extends EventEmitter { } unregisterSubscriber(topic, options) { - return this._whenReady() - .then(() => { - return this._masterApi.unregisterSubscriber( + return this._whenReady().then(() => { + return this._primaryApi.unregisterSubscriber( this._nodeName, topic, this._getXmlrpcUri(), @@ -244,9 +245,8 @@ class RosNode extends EventEmitter { } registerPublisher(topic, topicType, options) { - return this._whenReady() - .then(() => { - return this._masterApi.registerPublisher( + return this._whenReady().then(() => { + return this._primaryApi.registerPublisher( this._nodeName, topic, topicType, @@ -257,9 +257,8 @@ class RosNode extends EventEmitter { } unregisterPublisher(topic, options) { - return this._whenReady() - .then(() => { - return this._masterApi.unregisterPublisher( + return this._whenReady().then(() => { + return this._primaryApi.unregisterPublisher( this._nodeName, topic, this._getXmlrpcUri(), @@ -269,27 +268,31 @@ class RosNode extends EventEmitter { } lookupNode(nodeName, options) { - return this._masterApi.lookupNode(this._nodeName, nodeName, options); + return this._primaryApi.lookupNode(this._nodeName, nodeName, options); } lookupService(service, options) { - return this._masterApi.lookupService(this._nodeName, service, options); + return this._primaryApi.lookupService(this._nodeName, service, options); } - getMasterUri(options) { - return this._masterApi.getUri(this._nodeName, options); + getPrimaryUri(options) { + return this._primaryApi.getUri(this._nodeName, options); } getPublishedTopics(subgraph, options) { - return this._masterApi.getPublishedTopics(this._nodeName, subgraph, options); + return this._primaryApi.getPublishedTopics( + this._nodeName, + subgraph, + options + ); } getTopicTypes(options) { - return this._masterApi.getTopicTypes(this._nodeName, options); + return this._primaryApi.getTopicTypes(this._nodeName, options); } getSystemState(options) { - return this._masterApi.getSystemState(this._nodeName, options); + return this._primaryApi.getSystemState(this._nodeName, options); } /** @@ -299,26 +302,25 @@ class RosNode extends EventEmitter { * @private */ _whenReady() { - if (this.slaveApiSetupComplete()) { + if (this.assistantApiSetupComplete()) { return Promise.resolve(); - } - else { + } else { return new Promise((resolve, reject) => { - this.on('slaveApiSetupComplete', () => { + this.on("assistantApiSetupComplete", () => { resolve(); }); - }) + }); } } _getXmlrpcUri() { // TODO: get host or ip or ... - return 'http://' + NetworkUtils.getHost() + ':' + this._xmlrpcPort; + return "http://" + NetworkUtils.getHost() + ":" + this._xmlrpcPort; } -//------------------------------------------------------------------ -// Parameter Server API -//------------------------------------------------------------------ + //------------------------------------------------------------------ + // Parameter Server API + //------------------------------------------------------------------ deleteParam(key) { return this._paramServerApi.deleteParam(this._nodeName, key); @@ -335,9 +337,9 @@ class RosNode extends EventEmitter { hasParam(key) { return this._paramServerApi.hasParam(this._nodeName, key); } -//------------------------------------------------------------------ -// Slave API -//------------------------------------------------------------------ + //------------------------------------------------------------------ + // Assistant API + //------------------------------------------------------------------ /** * Send a topic request to another ros node @@ -349,12 +351,12 @@ class RosNode extends EventEmitter { requestTopic(remoteAddress, remotePort, topic, protocols) { // every time we request a topic, it could be from a new node // so we create an xmlrpc client here instead of having a single one - // for this object, like we do with the MasterApiClient - let slaveApi = new SlaveApiClient(remoteAddress, remotePort); - return slaveApi.requestTopic(this._nodeName, topic, protocols); + // for this object, like we do with the PrimaryApiClient + let assistantApi = new AssitantApiClient(remoteAddress, remotePort); + return assistantApi.requestTopic(this._nodeName, topic, protocols); } - slaveApiSetupComplete() { + assistantApiSetupComplete() { return !!this._xmlrpcPort; } @@ -366,52 +368,54 @@ class RosNode extends EventEmitter { return this._shutdown; } - _setupSlaveApi(xmlrpcPort=null) { + _setupAssistantApi(xmlrpcPort = null) { if (xmlrpcPort === null) { xmlrpcPort = 0; } return new Promise((resolve, reject) => { - const server = xmlrpc.createServer({port: xmlrpcPort}, () => { - const {port} = server.httpServer.address(); - this._debugLog.debug('Slave API Listening on port ' + port); + const server = xmlrpc.createServer({ port: xmlrpcPort }, () => { + const { port } = server.httpServer.address(); + this._debugLog.debug("Assistant API Listening on port " + port); this._xmlrpcPort = port; - resolve(port); - this.emit('slaveApiSetupComplete', port); + this.emit("assistantApiSetupComplete", port); }); - server.on('NotFound', (method, params) => { - this._log.warn('Method ' + method + ' does not exist: ' + params); + server.on("NotFound", (method, params) => { + this._log.warn("Method " + method + " does not exist: " + params); }); - server.on('requestTopic', this._handleTopicRequest.bind(this)); - server.on('publisherUpdate', this._handlePublisherUpdate.bind(this)); - server.on('paramUpdate', this._handleParamUpdate.bind(this)); - server.on('getPublications', this._handleGetPublications.bind(this)); - server.on('getSubscriptions', this._handleGetSubscriptions.bind(this)); - server.on('getPid', this._handleGetPid.bind(this)); - server.on('shutdown', this._handleShutdown.bind(this)); - server.on('getMasterUri', this._handleGetMasterUri.bind(this)); - server.on('getBusInfo', this._handleGetBusInfo.bind(this)); - server.on('getBusStats', this._handleGetBusStats.bind(this)); - - server.httpServer.on('clientError', (err, socket) => { - this._log.error('XMLRPC Server socket error: %j', err); + server.on("requestTopic", this._handleTopicRequest.bind(this)); + server.on("publisherUpdate", this._handlePublisherUpdate.bind(this)); + server.on("paramUpdate", this._handleParamUpdate.bind(this)); + server.on("getPublications", this._handleGetPublications.bind(this)); + server.on("getSubscriptions", this._handleGetSubscriptions.bind(this)); + server.on("getPid", this._handleGetPid.bind(this)); + server.on("shutdown", this._handleShutdown.bind(this)); + server.on("getPrimaryUri", this._handleGetPrimaryUri.bind(this)); + server.on("getBusInfo", this._handleGetBusInfo.bind(this)); + server.on("getBusStats", this._handleGetBusStats.bind(this)); + + server.httpServer.on("clientError", (err, socket) => { + this._log.error("XMLRPC Server socket error: %j", err); }); - this._slaveApiServer = server; + this._assistantApiServer = server; }); } - _setupTcprosServer(tcprosPort=null) { + _setupTcprosServer(tcprosPort = null) { let _createServer = (callback) => { const server = net.createServer((connection) => { - let conName = connection.remoteAddress + ":" - + connection.remotePort; + let conName = connection.remoteAddress + ":" + connection.remotePort; connection.name = conName; - this._debugLog.info('Node %s got connection from %s', this.getNodeName(), conName); + this._debugLog.info( + "Node %s got connection from %s", + this.getNodeName(), + conName + ); // data from connections will be TCPROS encoded, so use a // DeserializeStream to handle any chunking @@ -422,26 +426,34 @@ class RosNode extends EventEmitter { const checkConnectionHeader = (headerData) => { const header = tcprosUtils.parseTcpRosHeader(headerData); if (!header) { - this._log.error('Unable to validate connection header %s', headerData); - connection.end(tcprosUtils.serializeString('Unable to validate connection header')); + this._log.error( + "Unable to validate connection header %s", + headerData + ); + connection.end( + tcprosUtils.serializeString( + "Unable to validate connection header" + ) + ); return; } - this._debugLog.info('Got connection header: %j', header); + this._debugLog.info("Got connection header: %j", header); - if (header.hasOwnProperty('topic')) { + if (header.hasOwnProperty("topic")) { // this is a subscriber, validate header and pass off connection to appropriate publisher const topic = header.topic; const pub = this._publishers[topic]; if (pub) { pub.handleSubscriberConnection(connection, header); - } - else { + } else { // presumably this just means we shutdown the publisher after this // subscriber started trying to connect to us - this._log.info('Got connection header for unknown topic %s', topic); + this._log.info( + "Got connection header for unknown topic %s", + topic + ); } - } - else if (header.hasOwnProperty('service')) { + } else if (header.hasOwnProperty("service")) { // this is a service client, validate header and pass off connection to appropriate service provider const service = header.service; const serviceProvider = this._services[service]; @@ -450,7 +462,7 @@ class RosNode extends EventEmitter { } } }; - deserializeStream.once('message', checkConnectionHeader); + deserializeStream.once("message", checkConnectionHeader); }); if (tcprosPort === null) { @@ -461,14 +473,14 @@ class RosNode extends EventEmitter { this._tcprosServer = server; // it's possible the port was taken before we could use it - server.on('error', (err) => { - this._log.warn('Error on tcpros server! %j', err); + server.on("error", (err) => { + this._log.warn("Error on tcpros server! %j", err); }); // the port was available - server.on('listening', () => { - const {port} = server.address(); - this._debugLog.info('Listening on %j', server.address()); + server.on("listening", () => { + const { port } = server.address(); + this._debugLog.info("Listening on %j", server.address()); this._tcprosPort = port; callback(port); }); @@ -480,7 +492,7 @@ class RosNode extends EventEmitter { } _handleTopicRequest(err, params, callback) { - this._debugLog.info('Got topic request ' + JSON.stringify(params)); + this._debugLog.info("Got topic request " + JSON.stringify(params)); if (!err) { let topic = params[1]; let pub = this._publishers[topic]; @@ -488,63 +500,49 @@ class RosNode extends EventEmitter { let port = this._tcprosPort; let resp = [ 1, - 'Allocated topic connection on port ' + port, - [ - 'TCPROS', - NetworkUtils.getHost(), - port - ] + "Allocated topic connection on port " + port, + ["TCPROS", NetworkUtils.getHost(), port], ]; callback(null, resp); } - } - else { - this._log.error('Error during topic request: %s, %j', err, params); - let resp = [ - 0, - 'Unable to allocate topic connection for ' + topic, - [] - ]; - let err = 'Error: Unknown topic ' + topic; + } else { + this._log.error("Error during topic request: %s, %j", err, params); + let resp = [0, "Unable to allocate topic connection for " + topic, []]; + let err = "Error: Unknown topic " + topic; callback(err, resp); } } /** - * Handle publisher update message from master + * Handle publisher update message from primary * @param err was there an error * @param params {Array} [caller_id, topic, publishers] * @param callback function(err, resp) call when done handling message */ _handlePublisherUpdate(err, params, callback) { - this._debugLog.info('Publisher update ' + err + ' params: ' + JSON.stringify(params)); + this._debugLog.info( + "Publisher update " + err + " params: " + JSON.stringify(params) + ); let topic = params[1]; let sub = this._subscribers[topic]; if (sub) { - this._debugLog.info('Got sub for topic ' + topic); + this._debugLog.info("Got sub for topic " + topic); let pubs = params[2]; sub._handlePublisherUpdate(params[2]); - let resp = [ - 1, - 'Handled publisher update for topic ' + topic, - 0 - ]; + let resp = [1, "Handled publisher update for topic " + topic, 0]; callback(null, resp); - } - else { + } else { this._debugLog.warn(`Got publisher update for unknown topic ${topic}`); - let resp = [ - 0, - 'Don\'t have topic ' + topic, - 0 - ]; - let err = 'Error: Unknown topic ' + topic; + let resp = [0, "Don't have topic " + topic, 0]; + let err = "Error: Unknown topic " + topic; callback(err, resp); } } _handleParamUpdate(err, params, callback) { - this._log.info('Got param update! Not really doing anything with it...' + params); + this._log.info( + "Got param update! Not really doing anything with it..." + params + ); } _handleGetPublications(err, params, callback) { @@ -555,8 +553,8 @@ class RosNode extends EventEmitter { }); let resp = [ 1, - 'Returning list of publishers on node ' + this._nodeName, - pubs + "Returning list of publishers on node " + this._nodeName, + pubs, ]; callback(null, resp); } @@ -569,28 +567,28 @@ class RosNode extends EventEmitter { }); let resp = [ 1, - 'Returning list of publishers on node ' + this._nodeName, - subs + "Returning list of publishers on node " + this._nodeName, + subs, ]; callback(null, resp); } _handleGetPid(err, params, callback) { let caller = params[0]; - callback(null, [1, 'Returning process id', process.pid]); + callback(null, [1, "Returning process id", process.pid]); } _handleShutdown(err, params, callback) { let caller = params[0]; - this._log.warn('Received shutdown command from ' + caller); + this._log.warn("Received shutdown command from " + caller); return this.shutdown(); } - _handleGetMasterUri(err, params, callback) { + _handleGetPrimaryUri(err, params, callback) { let resp = [ 1, - 'Returning master uri for node ' + this._nodeName, - this._rosMasterAddress + "Returning primary uri for node " + this._nodeName, + this._rosPrimaryAddress, ]; callback(null, resp); } @@ -601,41 +599,23 @@ class RosNode extends EventEmitter { Object.keys(this._subscribers).forEach((topic) => { const sub = this._subscribers[topic]; sub.getClientUris().forEach((clientUri) => { - busInfo.push([ - ++count, - clientUri, - 'i', - 'TCPROS', - sub.getTopic(), - true - ]); + busInfo.push([++count, clientUri, "i", "TCPROS", sub.getTopic(), true]); }); }); Object.keys(this._publishers).forEach((topic) => { const pub = this._publishers[topic]; pub.getClientUris().forEach((clientUri) => { - busInfo.push([ - ++count, - clientUri, - 'o', - 'TCPROS', - pub.getTopic(), - true - ]); + busInfo.push([++count, clientUri, "o", "TCPROS", pub.getTopic(), true]); }); }); - const resp = [ - 1, - this.getNodeName(), - busInfo - ]; + const resp = [1, this.getNodeName(), busInfo]; callback(null, resp); } _handleGetBusStats(err, params, callback) { - this._log.error('Not implemented'); + this._log.error("Not implemented"); } /** @@ -647,7 +627,7 @@ class RosNode extends EventEmitter { if (spinnerOpts) { const { type } = spinnerOpts; switch (type) { - case 'Global': + case "Global": this._spinner = new GlobalSpinner(spinnerOpts); break; default: @@ -656,8 +636,7 @@ class RosNode extends EventEmitter { this._spinner = spinnerOpts; break; } - } - else { + } else { this._spinner = new GlobalSpinner(); } } @@ -669,50 +648,51 @@ class RosNode extends EventEmitter { let exitHandler; let sigIntHandler; - let exitImpl = function(killProcess=false) { + let exitImpl = function (killProcess = false) { this._shutdown = true; - this.emit('shutdown'); + this.emit("shutdown"); - this._log.info('Ros node ' + this._nodeName + ' beginning shutdown at ' + Date.now()); + this._log.info( + "Ros node " + this._nodeName + " beginning shutdown at " + Date.now() + ); const clearXmlrpcQueues = () => { - this._masterApi.getXmlrpcClient().clear(); + this._primaryApi.getXmlrpcClient().clear(); }; const shutdownServer = (server, name) => { return new Promise((resolve) => { const timeout = setTimeout(() => { - this._log.info('Timed out shutting down %s server', name); + this._log.info("Timed out shutting down %s server", name); resolve(); }, 200); server.close(() => { clearTimeout(timeout); - this._log.info('Server %s shutdown', name); + this._log.info("Server %s shutdown", name); resolve(); }); - }) - .catch((err) => { + }).catch((err) => { // no op - this._log.warn('Error shutting down server %s: %s', name, err); + this._log.warn("Error shutting down server %s: %s", name, err); }); }; // shutdown servers first so we don't accept any new connections // while unregistering const promises = [ - shutdownServer(this._slaveApiServer, 'slaveapi'), - shutdownServer(this._tcprosServer, 'tcpros') + shutdownServer(this._assistantApiServer, "assistantapi"), + shutdownServer(this._tcprosServer, "tcpros"), ]; // clear out any existing calls that may block us when we try to unregister clearXmlrpcQueues(); // remove all publishers, subscribers, and services. - // remove subscribers first so that master doesn't send + // remove subscribers first so that primary doesn't send // publisherUpdate messages. // set maxAttempts so that we don't spend forever trying to connect - // to a possibly non-existant ROS master. + // to a possibly non-existant ROS primary. const unregisterPromises = []; Object.keys(this._subscribers).forEach((topic) => { unregisterPromises.push(this.unsubscribe(topic, { maxAttempts: 1 })); @@ -723,41 +703,44 @@ class RosNode extends EventEmitter { }); Object.keys(this._services).forEach((service) => { - unregisterPromises.push(this.unadvertiseService(service, { maxAttempts: 1 })); + unregisterPromises.push( + this.unadvertiseService(service, { maxAttempts: 1 }) + ); }); // catch any errors while unregistering // and don't bother external callers about it. promises.push( Promise.all(unregisterPromises) - .then((err) => { - this._log.info('Finished unregistering from ROS master!'); - }) - .catch((err) => { - // no-op - this._log.warn('Error unregistering from ROS master: %s', err); - // TODO: should we check that err.code === 'ECONNREFUSED'?? - }) - .then(() => { - // clear out anything that's left - clearXmlrpcQueues(); - }) + .then((err) => { + this._log.info("Finished unregistering from ROS primary!"); + }) + .catch((err) => { + // no-op + this._log.warn("Error unregistering from ROS primary: %s", err); + // TODO: should we check that err.code === 'ECONNREFUSED'?? + }) + .then(() => { + // clear out anything that's left + clearXmlrpcQueues(); + }) ); this._spinner.clear(); Logging.stopLogCleanup(); - process.removeListener('exit', exitHandler); - process.removeListener('SIGINT', sigIntHandler); + process.removeListener("exit", exitHandler); + process.removeListener("SIGINT", sigIntHandler); if (killProcess) { // we can't really block the exit process, just have to hope it worked... - return Promise.all(promises).then(() => { - process.exit(); - }) - .catch((err) => { - process.exit(); - }) + return Promise.all(promises) + .then(() => { + process.exit(); + }) + .catch((err) => { + process.exit(); + }); } // else return Promise.all(promises); @@ -768,8 +751,8 @@ class RosNode extends EventEmitter { exitHandler = exitImpl.bind(this); sigIntHandler = exitImpl.bind(this, true); - process.once('exit', exitHandler ); - process.once('SIGINT', sigIntHandler ); + process.once("exit", exitHandler); + process.once("SIGINT", sigIntHandler); } } diff --git a/src/lib/ServiceClient.js b/src/lib/ServiceClient.js index e163199..6fb46fc 100644 --- a/src/lib/ServiceClient.js +++ b/src/lib/ServiceClient.js @@ -17,18 +17,18 @@ "use strict"; -let net = require('net'); -let NetworkUtils = require('../utils/network_utils.js'); -const ros_msg_utils = require('../ros_msg_utils'); +let net = require("net"); +let NetworkUtils = require("../utils/network_utils.js"); +const ros_msg_utils = require("../ros_msg_utils"); const base_serializers = ros_msg_utils.Serialize; -let SerializationUtils = require('../utils/serialization_utils.js'); +let SerializationUtils = require("../utils/serialization_utils.js"); let DeserializeStream = SerializationUtils.DeserializeStream; let Deserialize = SerializationUtils.Deserialize; let Serialize = SerializationUtils.Serialize; -let TcprosUtils = require('../utils/tcpros_utils.js'); -let EventEmitter = require('events'); -let Logging = require('./Logging.js'); -const {REGISTERED, SHUTDOWN} = require('../utils/ClientStates.js'); +let TcprosUtils = require("../utils/tcpros_utils.js"); +let EventEmitter = require("events"); +let Logging = require("./Logging.js"); +const { REGISTERED, SHUTDOWN } = require("../utils/ClientStates.js"); /** * @class ServiceCall @@ -68,12 +68,14 @@ class ServiceClient extends EventEmitter { this._calling = false; - this._log = Logging.getLogger('ros.rosnodejs'); + this._log = Logging.getLogger("ros.rosnodejs"); this._nodeHandle = nodeHandle; if (!options.typeClass) { - throw new Error(`Unable to load service for service client ${this.getService()} with type ${this.getType()}`); + throw new Error( + `Unable to load service for service client ${this.getService()} with type ${this.getType()}` + ); } this._messageHandler = options.typeClass; @@ -87,7 +89,7 @@ class ServiceClient extends EventEmitter { // waiting to get registered either so REGISTERING doesn't make sense... // Hence, we'll just call it REGISTERED. this._state = REGISTERED; - }; + } getService() { return this._service; @@ -115,7 +117,7 @@ class ServiceClient extends EventEmitter { shutdown() { this._state = SHUTDOWN; if (this._currentCall) { - this._currentCall.reject('SHUTDOWN'); + this._currentCall.reject("SHUTDOWN"); } } @@ -133,10 +135,15 @@ class ServiceClient extends EventEmitter { this._callQueue.push(newCall); // shift off old calls if user specified a max queue length - if (this._maxQueueLength > 0 && this._callQueue.length > this._maxQueueLength) { + if ( + this._maxQueueLength > 0 && + this._callQueue.length > this._maxQueueLength + ) { const oldCall = this._callQueue.shift(); - const err = new Error('Unable to complete service call because of queue limitations'); - err.code = 'E_ROSSERVICEQUEUEFULL'; + const err = new Error( + "Unable to complete service call because of queue limitations" + ); + err.code = "E_ROSSERVICEQUEUEFULL"; oldCall.reject(err); } @@ -151,9 +158,8 @@ class ServiceClient extends EventEmitter { _executeCall() { if (this.isShutdown()) { return; - } - else if (this._callQueue.length === 0) { - this._log.warn('Tried executing service call on empty queue'); + } else if (this._callQueue.length === 0) { + this._log.warn("Tried executing service call on empty queue"); return; } // else @@ -162,37 +168,39 @@ class ServiceClient extends EventEmitter { this._calling = true; this._initiateServiceConnection(call) - .then(() => { - this._throwIfShutdown(); - - return this._sendRequest(call); - }) - .then((msg) => { - this._throwIfShutdown(); - - this._calling = false; - this._currentCall = null; - - this._scheduleNextCall(); - - call.resolve(msg); - }) - .catch((err) => { - if (!this.isShutdown()) { - // this probably just means the service didn't exist yet - don't complain about it - // We should still reject the call - if (err.code !== 'EROSAPIERROR') { - this._log.error(`Error during service ${this.getService()} call ${err}`); - } + .then(() => { + this._throwIfShutdown(); + + return this._sendRequest(call); + }) + .then((msg) => { + this._throwIfShutdown(); this._calling = false; this._currentCall = null; this._scheduleNextCall(); - call.reject(err); - } - }); + call.resolve(msg); + }) + .catch((err) => { + if (!this.isShutdown()) { + // this probably just means the service didn't exist yet - don't complain about it + // We should still reject the call + if (err.code !== "EROSAPIERROR") { + this._log.error( + `Error during service ${this.getService()} call ${err}` + ); + } + + this._calling = false; + this._currentCall = null; + + this._scheduleNextCall(); + + call.reject(err); + } + }); } _scheduleNextCall() { @@ -206,8 +214,7 @@ class ServiceClient extends EventEmitter { // this will always be the case unless this is persistent service client // calling for a second time. if (!this.getPersist() || this._serviceClient === null) { - return this._nodeHandle.lookupService(this.getService()) - .then((resp) => { + return this._nodeHandle.lookupService(this.getService()).then((resp) => { this._throwIfShutdown(); const serviceUri = resp[2]; @@ -216,8 +223,7 @@ class ServiceClient extends EventEmitter { // connect to the service's tcpros server return this._connectToService(serviceHost, call); }); - } - else { + } else { // this is a persistent service that we've already set up call.serviceClient = this._serviceClient; return Promise.resolve(); @@ -230,48 +236,56 @@ class ServiceClient extends EventEmitter { } // serialize request - const serializedRequest = TcprosUtils.serializeMessage(this._messageHandler.Request, call.request); + const serializedRequest = TcprosUtils.serializeMessage( + this._messageHandler.Request, + call.request + ); call.serviceClient.write(serializedRequest); return new Promise((resolve, reject) => { const closeHandler = () => { - this._log.debug('Service %s client disconnected during call!', this.getService()); - reject(new Error('Connection was closed')); - } + this._log.debug( + "Service %s client disconnected during call!", + this.getService() + ); + reject(new Error("Connection was closed")); + }; - call.serviceClient.$deserializeStream.once('message', (msg, success) => { - call.serviceClient.removeListener('close', closeHandler); + call.serviceClient.$deserializeStream.once("message", (msg, success) => { + call.serviceClient.removeListener("close", closeHandler); if (success) { resolve(this._messageHandler.Response.deserialize(msg)); - } - else { + } else { const error = new Error(msg); - error.code = 'E_ROSSERVICEFAILED'; + error.code = "E_ROSSERVICEFAILED"; reject(error); } }); // if the connection closes while waiting for a response, reject the request - call.serviceClient.on('close', closeHandler); + call.serviceClient.on("close", closeHandler); }); } _connectToService(serviceHost, call) { return new Promise((resolve, reject) => { - this._log.debug('Service client %s connecting to %j', this.getService(), serviceHost); + this._log.debug( + "Service client %s connecting to %j", + this.getService(), + serviceHost + ); this._createCallSocketAndHandlers(serviceHost, call, reject); this._cacheSocketIfPersistent(call); - let deserializer = new DeserializeStream(); call.serviceClient.$deserializeStream = deserializer; call.serviceClient.pipe(deserializer); - deserializer.once('message', (msg) => { + deserializer.once("message", (msg) => { if (!call.serviceClient.$initialized) { let header = TcprosUtils.parseTcpRosHeader(msg); if (header.error) { @@ -291,18 +305,25 @@ class ServiceClient extends EventEmitter { _createCallSocketAndHandlers(serviceHost, call, reject) { // create a socket connection to the service provider call.serviceClient = net.connect(serviceHost, () => { - // Connection to service's TCPROS server succeeded - generate and send a connection header - this._log.debug('Sending service client %s connection header', this.getService()); - - let serviceClientHeader = TcprosUtils.createServiceClientHeader(this._nodeHandle.getNodeName(), - this.getService(), this._messageHandler.md5sum(), this.getType(), this.getPersist()); + this._log.debug( + "Sending service client %s connection header", + this.getService() + ); + + let serviceClientHeader = TcprosUtils.createServiceClientHeader( + this._nodeHandle.getNodeName(), + this.getService(), + this._messageHandler.md5sum(), + this.getType(), + this.getPersist() + ); call.serviceClient.write(serviceClientHeader); }); // bind a close handling function - call.serviceClient.on('close', () => { + call.serviceClient.on("close", () => { call.serviceClient = null; // we could probably just always reset this._serviceClient to null here but... if (this.getPersist()) { @@ -312,7 +333,7 @@ class ServiceClient extends EventEmitter { // bind an error function - any errors connecting to the service // will cause the call to be rejected (in this._executeCall) - call.serviceClient.on('error', (err) => { + call.serviceClient.on("error", (err) => { this._log.info(`Service Client ${this.getService()} error: ${err}`); reject(err); }); @@ -320,7 +341,7 @@ class ServiceClient extends EventEmitter { _cacheSocketIfPersistent(call) { // If this is a persistent service client, we're here because we haven't connected to this service before. - // Cache the service client for later use. Future calls won't need to lookup the service with the ROS master + // Cache the service client for later use. Future calls won't need to lookup the service with the ROS primary // or deal with the connection header. if (this.getPersist()) { this._serviceClient = call.serviceClient; @@ -329,7 +350,7 @@ class ServiceClient extends EventEmitter { _throwIfShutdown() { if (this.isShutdown()) { - throw new Error('SHUTDOWN'); + throw new Error("SHUTDOWN"); } } } diff --git a/src/lib/ServiceServer.js b/src/lib/ServiceServer.js index 7f58a03..dc691ce 100644 --- a/src/lib/ServiceServer.js +++ b/src/lib/ServiceServer.js @@ -17,18 +17,22 @@ "use strict"; -const net = require('net'); -const NetworkUtils = require('../utils/network_utils.js'); -const ros_msg_utils = require('../ros_msg_utils'); +const net = require("net"); +const NetworkUtils = require("../utils/network_utils.js"); +const ros_msg_utils = require("../ros_msg_utils"); const base_serializers = ros_msg_utils.Serialize; -const SerializationUtils = require('../utils/serialization_utils.js'); +const SerializationUtils = require("../utils/serialization_utils.js"); const DeserializeStream = SerializationUtils.DeserializeStream; const Deserialize = SerializationUtils.Deserialize; const Serialize = SerializationUtils.Serialize; -const TcprosUtils = require('../utils/tcpros_utils.js'); -const EventEmitter = require('events'); -const Logging = require('./Logging.js'); -const {REGISTERING, REGISTERED, SHUTDOWN} = require('../utils/ClientStates.js'); +const TcprosUtils = require("../utils/tcpros_utils.js"); +const EventEmitter = require("events"); +const Logging = require("./Logging.js"); +const { + REGISTERING, + REGISTERED, + SHUTDOWN, +} = require("../utils/ClientStates.js"); class ServiceServer extends EventEmitter { constructor(options, callback, nodeHandle) { @@ -41,12 +45,14 @@ class ServiceServer extends EventEmitter { this._nodeHandle = nodeHandle; - this._log = Logging.getLogger('ros.rosnodejs'); + this._log = Logging.getLogger("ros.rosnodejs"); this._requestCallback = callback; if (!options.typeClass) { - throw new Error(`Unable to load service for service ${this.getService()} with type ${this.getType()}`); + throw new Error( + `Unable to load service for service ${this.getService()} with type ${this.getType()}` + ); } this._messageHandler = options.typeClass; @@ -55,7 +61,7 @@ class ServiceServer extends EventEmitter { this._state = REGISTERING; this._register(); - }; + } getService() { return this._service; @@ -84,7 +90,7 @@ class ServiceServer extends EventEmitter { /** * The ROS client shutdown code is a little noodly. Users can close a client through * the ROS node or the client itself and both are correct. Either through a node.unadvertise() - * call or a client.shutdown() call - in both instances a call needs to be made to the ROS master + * call or a client.shutdown() call - in both instances a call needs to be made to the ROS primary * and the client needs to tear itself down. */ shutdown() { @@ -116,47 +122,59 @@ class ServiceServer extends EventEmitter { } // else // TODO: verify header data - this._log.debug('Service %s handling new client connection ', this.getService()); - - const error = TcprosUtils.validateServiceClientHeader(header, this.getService(), this._messageHandler.md5sum()); + this._log.debug( + "Service %s handling new client connection ", + this.getService() + ); + + const error = TcprosUtils.validateServiceClientHeader( + header, + this.getService(), + this._messageHandler.md5sum() + ); if (error) { - this._log.error('Error while validating service %s connection header: %s', this.getService(), error); + this._log.error( + "Error while validating service %s connection header: %s", + this.getService(), + error + ); client.end(Serialize(TcprosUtils.createTcpRosError(error))); return; } - let respHeader = - TcprosUtils.createServiceServerHeader( - this._nodeHandle.getNodeName(), - this._messageHandler.md5sum(), - this.getType()); + let respHeader = TcprosUtils.createServiceServerHeader( + this._nodeHandle.getNodeName(), + this._messageHandler.md5sum(), + this.getType() + ); client.write(respHeader); - client.$persist = (header['persistent'] === '1'); + client.$persist = header["persistent"] === "1"; // bind to message handler client.$messageHandler = this._handleMessage.bind(this, client); - client.$deserializeStream.on('message', client.$messageHandler); + client.$deserializeStream.on("message", client.$messageHandler); - client.on('close', () => { + client.on("close", () => { delete this._clients[client.name]; - this._log.debug('Service client %s disconnected!', client.name); + this._log.debug("Service client %s disconnected!", client.name); }); this._clients[client.name] = client; - this.emit('connection', header, client.name); + this.emit("connection", header, client.name); } _handleMessage(client, data) { - this._log.trace('Service ' + this.getService() + ' got message! ' + data.toString('hex')); + this._log.trace( + "Service " + this.getService() + " got message! " + data.toString("hex") + ); // deserialize msg const req = this._messageHandler.Request.deserialize(data); // call service callback let resp = new this._messageHandler.Response(); let result = this._requestCallback(req, resp); - Promise.resolve(result) - .then((success) => { + Promise.resolve(result).then((success) => { // client should already have been closed, so if we got here just cut out early if (this.isShutdown()) { return; @@ -172,7 +190,7 @@ class ServiceServer extends EventEmitter { client.write(serializeResponse); if (!client.$persist) { - this._log.debug('Closing non-persistent client'); + this._log.debug("Closing non-persistent client"); client.end(); delete this._clients[client.name]; } @@ -180,15 +198,14 @@ class ServiceServer extends EventEmitter { } _register() { - this._nodeHandle.registerService(this.getService()) - .then((resp) => { + this._nodeHandle.registerService(this.getService()).then((resp) => { // if we were shutdown between the starting the registration and now, bail if (this.isShutdown()) { return; } this._state = REGISTERED; - this.emit('registered'); + this.emit("registered"); }); } } diff --git a/src/lib/SlaveApiClient.js b/src/lib/SlaveApiClient.js index f176c11..a365417 100644 --- a/src/lib/SlaveApiClient.js +++ b/src/lib/SlaveApiClient.js @@ -21,7 +21,7 @@ let xmlrpc = require('xmlrpc'); //----------------------------------------------------------------------- -class SlaveApiClient { +class AssitantApiClient { constructor(host, port) { this._xmlrpcClient = xmlrpc.createClient({host: host, port: port}); @@ -44,4 +44,4 @@ class SlaveApiClient { //----------------------------------------------------------------------- -module.exports = SlaveApiClient; +module.exports = AssitantApiClient; diff --git a/src/lib/Subscriber.js b/src/lib/Subscriber.js index a9eb89d..a5f6586 100644 --- a/src/lib/Subscriber.js +++ b/src/lib/Subscriber.js @@ -17,9 +17,9 @@ "use strict"; -const EventEmitter = require('events'); -const Ultron = require('ultron'); -const {rebroadcast} = require('../utils/event_utils.js'); +const EventEmitter = require("events"); +const Ultron = require("ultron"); +const { rebroadcast } = require("../utils/event_utils.js"); //----------------------------------------------------------------------- @@ -39,11 +39,11 @@ class Subscriber extends EventEmitter { this._topic = impl.getTopic(); this._type = impl.getType(); - rebroadcast('registered', this._ultron, this); - rebroadcast('connection', this._ultron, this); - rebroadcast('disconnect', this._ultron, this); - rebroadcast('error', this._ultron, this); - rebroadcast('message', this._ultron, this); + rebroadcast("registered", this._ultron, this); + rebroadcast("connection", this._ultron, this); + rebroadcast("disconnect", this._ultron, this); + rebroadcast("error", this._ultron, this); + rebroadcast("message", this._ultron, this); } /** @@ -77,12 +77,12 @@ class Subscriber extends EventEmitter { /** * Shuts down this subscriber. If this is the last subscriber on this topic - * for this node, closes the subscriber and unregisters the topic from Master + * for this node, closes the subscriber and unregisters the topic from Primary * @returns {Promise} */ shutdown() { if (this._impl) { - const impl = this._impl + const impl = this._impl; this._impl = null; this._ultron.destroy(); this._ultron = null; diff --git a/src/lib/impl/PublisherImpl.js b/src/lib/impl/PublisherImpl.js index d395549..194e39d 100644 --- a/src/lib/impl/PublisherImpl.js +++ b/src/lib/impl/PublisherImpl.js @@ -17,12 +17,16 @@ "use strict"; -const SerializationUtils = require('../../utils/serialization_utils.js'); +const SerializationUtils = require("../../utils/serialization_utils.js"); const Serialize = SerializationUtils.Serialize; -const TcprosUtils = require('../../utils/tcpros_utils.js'); -const EventEmitter = require('events'); -const Logging = require('../Logging.js'); -const {REGISTERING, REGISTERED, SHUTDOWN} = require('../../utils/ClientStates.js'); +const TcprosUtils = require("../../utils/tcpros_utils.js"); +const EventEmitter = require("events"); +const Logging = require("../Logging.js"); +const { + REGISTERING, + REGISTERED, + SHUTDOWN, +} = require("../../utils/ClientStates.js"); /** * Implementation class for a Publisher. Handles registration, connecting to @@ -41,12 +45,11 @@ class PublisherImpl extends EventEmitter { this._latching = !!options.latching; - this._tcpNoDelay = !!options.tcpNoDelay; + this._tcpNoDelay = !!options.tcpNoDelay; - if (options.hasOwnProperty('queueSize')) { + if (options.hasOwnProperty("queueSize")) { this._queueSize = options.queueSize; - } - else { + } else { this._queueSize = 1; } @@ -57,10 +60,9 @@ class PublisherImpl extends EventEmitter { * >= 0 : place event at end of event queue to publish message after minimum delay (MS) */ - if (options.hasOwnProperty('throttleMs')) { + if (options.hasOwnProperty("throttleMs")) { this._throttleMs = options.throttleMs; - } - else { + } else { this._throttleMs = 0; } @@ -73,14 +75,18 @@ class PublisherImpl extends EventEmitter { this._lastSentMsg = null; this._nodeHandle = nodeHandle; - this._nodeHandle.getSpinner().addClient(this, this._getSpinnerId(), this._queueSize, this._throttleMs); + this._nodeHandle + .getSpinner() + .addClient(this, this._getSpinnerId(), this._queueSize, this._throttleMs); - this._log = Logging.getLogger('ros.rosnodejs'); + this._log = Logging.getLogger("ros.rosnodejs"); this._subClients = {}; if (!options.typeClass) { - throw new Error(`Unable to load message for publisher ${this.getTopic()} with type ${this.getType()}`); + throw new Error( + `Unable to load message for publisher ${this.getTopic()} with type ${this.getType()}` + ); } this._messageHandler = options.typeClass; @@ -131,7 +137,7 @@ class PublisherImpl extends EventEmitter { /** * Get the list of client addresses connect to this publisher. - * Used for getBusInfo Slave API calls + * Used for getBusInfo Assistant API calls * @returns {Array} */ getClientUris() { @@ -151,7 +157,7 @@ class PublisherImpl extends EventEmitter { */ shutdown() { this._state = SHUTDOWN; - this._log.debug('Shutting down publisher %s', this.getTopic()); + this._log.debug("Shutting down publisher %s", this.getTopic()); Object.keys(this._subClients).forEach((clientId) => { const client = this._subClients[clientId]; @@ -182,15 +188,14 @@ class PublisherImpl extends EventEmitter { return; } - if (typeof throttleMs !== 'number') { + if (typeof throttleMs !== "number") { throttleMs = this._throttleMs; } if (throttleMs < 0) { // short circuit JS event queue, publish "synchronously" this._handleMsgQueue([msg]); - } - else { + } else { this._nodeHandle.getSpinner().ping(this._getSpinnerId(), msg); } } @@ -200,7 +205,6 @@ class PublisherImpl extends EventEmitter { * @param msgQueue {Array} Array of messages. Type of each message matches this._type */ _handleMsgQueue(msgQueue) { - // There's a small chance that we were shutdown while the spinner was locked // which could cause _handleMsgQueue to be called if this publisher was in there. if (this.isShutdown()) { @@ -209,7 +213,10 @@ class PublisherImpl extends EventEmitter { const numClients = this.getNumSubscribers(); if (numClients === 0) { - this._log.debugThrottle(2000, `Publishing message on ${this.getTopic()} with no subscribers`); + this._log.debugThrottle( + 2000, + `Publishing message on ${this.getTopic()} with no subscribers` + ); } try { @@ -218,7 +225,10 @@ class PublisherImpl extends EventEmitter { msg = this._messageHandler.Resolve(msg); } - const serializedMsg = TcprosUtils.serializeMessage(this._messageHandler, msg); + const serializedMsg = TcprosUtils.serializeMessage( + this._messageHandler, + msg + ); Object.keys(this._subClients).forEach((client) => { this._subClients[client].write(serializedMsg); @@ -231,10 +241,13 @@ class PublisherImpl extends EventEmitter { this._lastSentMsg = serializedMsg; } }); - } - catch (err) { - this._log.error('Error when publishing message on topic %s: %s', this.getTopic(), err.stack); - this.emit('error', err); + } catch (err) { + this._log.error( + "Error when publishing message on topic %s: %s", + this.getTopic(), + err.stack + ); + this.emit("error", err); } } @@ -246,88 +259,112 @@ class PublisherImpl extends EventEmitter { */ handleSubscriberConnection(socket, header) { let error = TcprosUtils.validateSubHeader( - header, this.getTopic(), this.getType(), - this._messageHandler.md5sum()); + header, + this.getTopic(), + this.getType(), + this._messageHandler.md5sum() + ); if (error !== null) { - this._log.error('Unable to validate subscriber connection header ' - + JSON.stringify(header)); + this._log.error( + "Unable to validate subscriber connection header " + + JSON.stringify(header) + ); socket.end(Serialize(error)); return; } // else - this._log.info('Pub %s got connection header %s', this.getTopic(), JSON.stringify(header)); + this._log.info( + "Pub %s got connection header %s", + this.getTopic(), + JSON.stringify(header) + ); // create and send response - let respHeader = - TcprosUtils.createPubHeader( - this._nodeHandle.getNodeName(), - this._messageHandler.md5sum(), - this.getType(), - this.getLatching(), - this._messageHandler.messageDefinition()); + let respHeader = TcprosUtils.createPubHeader( + this._nodeHandle.getNodeName(), + this._messageHandler.md5sum(), + this.getType(), + this.getLatching(), + this._messageHandler.messageDefinition() + ); socket.write(respHeader); // if this publisher had the tcpNoDelay option set // disable the nagle algorithm - if (this._tcpNoDelay || header.tcp_nodelay === '1') { + if (this._tcpNoDelay || header.tcp_nodelay === "1") { socket.setNoDelay(true); } - socket.on('close', () => { - this._log.info('Publisher client socket %s on topic %s disconnected', - socket.name, this.getTopic()); + socket.on("close", () => { + this._log.info( + "Publisher client socket %s on topic %s disconnected", + socket.name, + this.getTopic() + ); socket.removeAllListeners(); delete this._subClients[socket.name]; - this.emit('disconnect'); + this.emit("disconnect"); }); - socket.on('end', () => { - this._log.info('Publisher client socket %s on topic %s ended the connection', - socket.name, this.getTopic()); + socket.on("end", () => { + this._log.info( + "Publisher client socket %s on topic %s ended the connection", + socket.name, + this.getTopic() + ); }); - socket.on('error', (err) => { - this._log.warn('Publisher client socket %s on topic %s had error: %s', - socket.name, this.getTopic(), err); + socket.on("error", (err) => { + this._log.warn( + "Publisher client socket %s on topic %s had error: %s", + socket.name, + this.getTopic(), + err + ); }); // if we've cached a message from latching, send it now if (this._lastSentMsg !== null) { - this._log.debug('Sending latched msg to new subscriber'); + this._log.debug("Sending latched msg to new subscriber"); socket.write(this._lastSentMsg); } // handshake was good - we'll start publishing to it this._subClients[socket.name] = socket; - this.emit('connection', header, socket.name); + this.emit("connection", header, socket.name); } /** - * Makes an XMLRPC call to registers this publisher with the ROS master + * Makes an XMLRPC call to registers this publisher with the ROS primary */ _register() { - this._nodeHandle.registerPublisher(this._topic, this._type) - .then((resp) => { - // if we were shutdown between the starting the registration and now, bail - if (this.isShutdown()) { - return; - } - - this._log.info('Registered %s as a publisher: %j', this._topic, resp); - let code = resp[0]; - let msg = resp[1]; - let subs = resp[2]; - if (code === 1) { - // registration worked - this._state = REGISTERED; - this.emit('registered'); - } - }) - .catch((err) => { - this._log.error('Error while registering publisher %s: %s', this.getTopic(), err); - }) + this._nodeHandle + .registerPublisher(this._topic, this._type) + .then((resp) => { + // if we were shutdown between the starting the registration and now, bail + if (this.isShutdown()) { + return; + } + + this._log.info("Registered %s as a publisher: %j", this._topic, resp); + let code = resp[0]; + let msg = resp[1]; + let subs = resp[2]; + if (code === 1) { + // registration worked + this._state = REGISTERED; + this.emit("registered"); + } + }) + .catch((err) => { + this._log.error( + "Error while registering publisher %s: %s", + this.getTopic(), + err + ); + }); } } diff --git a/src/lib/impl/SubscriberImpl.js b/src/lib/impl/SubscriberImpl.js index 8f2c77d..37e418f 100644 --- a/src/lib/impl/SubscriberImpl.js +++ b/src/lib/impl/SubscriberImpl.js @@ -17,18 +17,22 @@ "use strict"; -const NetworkUtils = require('../../utils/network_utils.js'); -const SerializationUtils = require('../../utils/serialization_utils.js'); +const NetworkUtils = require("../../utils/network_utils.js"); +const SerializationUtils = require("../../utils/serialization_utils.js"); const DeserializeStream = SerializationUtils.DeserializeStream; -const Deserialize = SerializationUtils.Deserialize; +const Deserialize = SerializationUtils.Deserialize; const Serialize = SerializationUtils.Serialize; -const TcprosUtils = require('../../utils/tcpros_utils.js'); -const Socket = require('net').Socket; -const EventEmitter = require('events'); -const Logging = require('../Logging.js'); -const {REGISTERING, REGISTERED, SHUTDOWN} = require('../../utils/ClientStates.js'); - -const protocols = [['TCPROS']]; +const TcprosUtils = require("../../utils/tcpros_utils.js"); +const Socket = require("net").Socket; +const EventEmitter = require("events"); +const Logging = require("../Logging.js"); +const { + REGISTERING, + REGISTERED, + SHUTDOWN, +} = require("../../utils/ClientStates.js"); + +const protocols = [["TCPROS"]]; //----------------------------------------------------------------------- @@ -38,7 +42,6 @@ const protocols = [['TCPROS']]; * of this to use */ class SubscriberImpl extends EventEmitter { - constructor(options, nodeHandle) { super(); @@ -48,10 +51,9 @@ class SubscriberImpl extends EventEmitter { this._type = options.type; - if (options.hasOwnProperty('queueSize')) { + if (options.hasOwnProperty("queueSize")) { this._queueSize = options.queueSize; - } - else { + } else { this._queueSize = 1; } @@ -60,26 +62,29 @@ class SubscriberImpl extends EventEmitter { * < 0 : handle immediately - no interaction with queue * >= 0 : place event at end of event queue to handle after minimum delay (MS) */ - if (options.hasOwnProperty('throttleMs')) { + if (options.hasOwnProperty("throttleMs")) { this._throttleMs = options.throttleMs; - } - else { + } else { this._throttleMs = 0; } // tcpNoDelay will be set as a field in the connection header sent to the // relevant publisher - the publisher should then set tcpNoDelay on the socket - this._tcpNoDelay = !!options.tcpNoDelay; + this._tcpNoDelay = !!options.tcpNoDelay; this._msgHandleTime = null; this._nodeHandle = nodeHandle; - this._nodeHandle.getSpinner().addClient(this, this._getSpinnerId(), this._queueSize, this._throttleMs); + this._nodeHandle + .getSpinner() + .addClient(this, this._getSpinnerId(), this._queueSize, this._throttleMs); - this._log = Logging.getLogger('ros.rosnodejs'); + this._log = Logging.getLogger("ros.rosnodejs"); if (!options.typeClass) { - throw new Error(`Unable to load message for subscriber ${this.getTopic()} with type ${this.getType()}`); + throw new Error( + `Unable to load message for subscriber ${this.getTopic()} with type ${this.getType()}` + ); } this._messageHandler = options.typeClass; @@ -137,10 +142,12 @@ class SubscriberImpl extends EventEmitter { */ shutdown() { this._state = SHUTDOWN; - this._log.debug('Shutting down subscriber %s', this.getTopic()); + this._log.debug("Shutting down subscriber %s", this.getTopic()); Object.keys(this._pubClients).forEach(this._disconnectClient.bind(this)); - Object.keys(this._pendingPubClients).forEach(this._disconnectClient.bind(this)); + Object.keys(this._pendingPubClients).forEach( + this._disconnectClient.bind(this) + ); // disconnect from the spinner in case we have any pending callbacks this._nodeHandle.getSpinner().disconnect(this._getSpinnerId()); @@ -175,7 +182,7 @@ class SubscriberImpl extends EventEmitter { } /** - * Handle an update from the ROS master with the list of current publishers. Connect to any new ones + * Handle an update from the ROS primary with the list of current publishers. Connect to any new ones * and disconnect from any not included in the list. * @param publisherList {Array.string} * @private @@ -205,14 +212,20 @@ class SubscriberImpl extends EventEmitter { _requestTopicFromPublisher(pubUri) { let info = NetworkUtils.getAddressAndPortFromUri(pubUri); // send a topic request to the publisher's node - this._log.debug('Sending topic request to ' + JSON.stringify(info)); - this._nodeHandle.requestTopic(info.host, info.port, this._topic, protocols) + this._log.debug("Sending topic request to " + JSON.stringify(info)); + this._nodeHandle + .requestTopic(info.host, info.port, this._topic, protocols) .then((resp) => { this._handleTopicRequestResponse(resp, pubUri); }) .catch((err, resp) => { // there was an error in the topic request - this._log.warn('Error requesting topic on %s: %s, %s', this.getTopic(), err, resp); + this._log.warn( + "Error requesting topic on %s: %s, %s", + this.getTopic(), + err, + resp + ); }); } @@ -229,7 +242,11 @@ class SubscriberImpl extends EventEmitter { } if (client) { - this._log.debug('Subscriber %s disconnecting client %s', this.getTopic(), clientId); + this._log.debug( + "Subscriber %s disconnecting client %s", + this.getTopic(), + clientId + ); client.end(); client.removeAllListeners(); @@ -244,42 +261,47 @@ class SubscriberImpl extends EventEmitter { delete this._pendingPubClients[clientId]; if (hasValidatedClient) { - this.emit('disconnect'); + this.emit("disconnect"); } } } /** - * Registers the subscriber with the ROS master + * Registers the subscriber with the ROS primary * will connect to any existing publishers on the topic that are included in the response */ _register() { - this._nodeHandle.registerSubscriber(this._topic, this._type) - .then((resp) => { - // if we were shutdown between the starting the registration and now, bail - if (this.isShutdown()) { - return; - } + this._nodeHandle + .registerSubscriber(this._topic, this._type) + .then((resp) => { + // if we were shutdown between the starting the registration and now, bail + if (this.isShutdown()) { + return; + } - // else handle response from register subscriber call - let code = resp[0]; - let msg = resp[1]; - let pubs = resp[2]; - if ( code === 1 ) { - // success! update state to reflect that we're registered - this._state = REGISTERED; - - if (pubs.length > 0) { - // this means we're ok and that publishers already exist on this topic - // we should connect to them - this.requestTopicFromPubs(pubs); + // else handle response from register subscriber call + let code = resp[0]; + let msg = resp[1]; + let pubs = resp[2]; + if (code === 1) { + // success! update state to reflect that we're registered + this._state = REGISTERED; + + if (pubs.length > 0) { + // this means we're ok and that publishers already exist on this topic + // we should connect to them + this.requestTopicFromPubs(pubs); + } + this.emit("registered"); } - this.emit('registered'); - } - }) - .catch((err, resp) => { - this._log.warn('Error during subscriber %s registration: %s', this.getTopic(), err); - }) + }) + .catch((err, resp) => { + this._log.warn( + "Error during subscriber %s registration: %s", + this.getTopic(), + err + ); + }); } /** @@ -291,7 +313,7 @@ class SubscriberImpl extends EventEmitter { return; } - this._log.debug('Topic request response: ' + JSON.stringify(resp)); + this._log.debug("Topic request response: " + JSON.stringify(resp)); // resp[2] has port and address for where to connect let info = resp[2]; @@ -299,23 +321,33 @@ class SubscriberImpl extends EventEmitter { let address = info[1]; let socket = new Socket(); - socket.name = address + ':' + port; + socket.name = address + ":" + port; socket.nodeUri = nodeUri; - socket.on('end', () => { - this._log.info('Subscriber client socket %s on topic %s ended the connection', - socket.name, this.getTopic()); + socket.on("end", () => { + this._log.info( + "Subscriber client socket %s on topic %s ended the connection", + socket.name, + this.getTopic() + ); }); - socket.on('error', (err) => { - this._log.warn('Subscriber client socket %s on topic %s had error: %s', - socket.name, this.getTopic(), err); + socket.on("error", (err) => { + this._log.warn( + "Subscriber client socket %s on topic %s had error: %s", + socket.name, + this.getTopic(), + err + ); }); // hook into close event to clean things up - socket.on('close', () => { - this._log.info('Subscriber client socket %s on topic %s disconnected', - socket.name, this.getTopic()); + socket.on("close", () => { + this._log.info( + "Subscriber client socket %s on topic %s disconnected", + socket.name, + this.getTopic() + ); this._disconnectClient(socket.nodeUri); }); @@ -326,7 +358,14 @@ class SubscriberImpl extends EventEmitter { return; } - this._log.debug('Subscriber on ' + this.getTopic() + ' connected to publisher at ' + address + ':' + port); + this._log.debug( + "Subscriber on " + + this.getTopic() + + " connected to publisher at " + + address + + ":" + + port + ); socket.write(this._createTcprosHandshake()); }); @@ -342,7 +381,10 @@ class SubscriberImpl extends EventEmitter { // create a one-time handler for the connection header // if the connection is validated, we'll listen for more events - deserializer.once('message', this._handleConnectionHeader.bind(this, socket)); + deserializer.once( + "message", + this._handleConnectionHeader.bind(this, socket) + ); } /** @@ -350,8 +392,14 @@ class SubscriberImpl extends EventEmitter { * @returns {string} */ _createTcprosHandshake() { - return TcprosUtils.createSubHeader(this._nodeHandle.getNodeName(), this._messageHandler.md5sum(), - this.getTopic(), this.getType(), this._messageHandler.messageDefinition(), this._tcpNoDelay); + return TcprosUtils.createSubHeader( + this._nodeHandle.getNodeName(), + this._messageHandler.md5sum(), + this.getTopic(), + this.getType(), + this._messageHandler.messageDefinition(), + this._tcpNoDelay + ); } /** @@ -374,14 +422,27 @@ class SubscriberImpl extends EventEmitter { } // now do our own validation of the publisher's header - const error = TcprosUtils.validatePubHeader(header, this.getType(), this._messageHandler.md5sum()); + const error = TcprosUtils.validatePubHeader( + header, + this.getType(), + this._messageHandler.md5sum() + ); if (error) { - this._log.error(`Unable to validate subscriber ${this.getTopic()} connection header ${JSON.stringify(header)}`); + this._log.error( + `Unable to validate subscriber ${this.getTopic()} connection header ${JSON.stringify( + header + )}` + ); socket.end(Serialize(error)); return; } // connection header was valid - we're good to go! - this._log.debug('Subscriber ' + this.getTopic() + ' got connection header ' + JSON.stringify(header)); + this._log.debug( + "Subscriber " + + this.getTopic() + + " got connection header " + + JSON.stringify(header) + ); // cache client now that we've verified the connection header this._pubClients[socket.nodeUri] = socket; @@ -389,9 +450,9 @@ class SubscriberImpl extends EventEmitter { delete this._pendingPubClients[socket.nodeUri]; // pipe all future messages to _handleMessage - socket.$deserializer.on('message', this._handleMessage.bind(this)); + socket.$deserializer.on("message", this._handleMessage.bind(this)); - this.emit('connection', header, socket.name); + this.emit("connection", header, socket.name); } /** @@ -402,8 +463,7 @@ class SubscriberImpl extends EventEmitter { _handleMessage(msg) { if (this._throttleMs < 0) { this._handleMsgQueue([msg]); - } - else { + } else { this._nodeHandle.getSpinner().ping(this._getSpinnerId(), msg); } } @@ -415,12 +475,15 @@ class SubscriberImpl extends EventEmitter { _handleMsgQueue(msgQueue) { try { msgQueue.forEach((msg) => { - this.emit('message', this._messageHandler.deserialize(msg)); + this.emit("message", this._messageHandler.deserialize(msg)); }); - } - catch (err) { - this._log.error('Error while dispatching message on topic %s: %s', this.getTopic(), err); - this.emit('error', err); + } catch (err) { + this._log.error( + "Error while dispatching message on topic %s: %s", + this.getTopic(), + err + ); + this.emit("error", err); } } } diff --git a/src/utils/remapping_utils.js b/src/utils/remapping_utils.js index b3a12cb..85d3e31 100644 --- a/src/utils/remapping_utils.js +++ b/src/utils/remapping_utils.js @@ -1,11 +1,10 @@ - const SPECIAL_KEYS = { - name: '__name', - log: '__log', // I don't think rosnodejs is responsible for changing the log directory - ip: '__ip', - hostname: '__hostname', - master: '__master', - ns: '__ns' + name: "__name", + log: "__log", // I don't think rosnodejs is responsible for changing the log directory + ip: "__ip", + hostname: "__hostname", + primary: "__primary", + ns: "__ns", }; const RemapUtils = { @@ -17,17 +16,17 @@ const RemapUtils = { for (let i = 0; i < len; ++i) { const arg = args[i]; - let p = arg.indexOf(':='); + let p = arg.indexOf(":="); if (p >= 0) { const local = arg.substring(0, p); - const external = arg.substring(p+2); + const external = arg.substring(p + 2); remapping[local] = external; } } return remapping; - } -} + }, +}; module.exports = RemapUtils; diff --git a/test/Log.js b/test/Log.js index 8f28e83..ee9b1ff 100644 --- a/test/Log.js +++ b/test/Log.js @@ -1,12 +1,12 @@ -'use strict'; +"use strict"; -const chai = require('chai'); +const chai = require("chai"); const expect = chai.expect; -const bunyan = require('bunyan'); -const xmlrpc = require('xmlrpc'); -const rosnodejs = require('../src/index.js'); +const bunyan = require("bunyan"); +const xmlrpc = require("xmlrpc"); +const rosnodejs = require("../src/index.js"); -const MASTER_PORT = 11234; +const PRIMARY_PORT = 11234; /** setup pipe to stdout **/ class OutputCapture { @@ -27,11 +27,11 @@ class OutputCapture { } } -describe('Logging', () => { +describe("Logging", () => { const outputCapture = new OutputCapture(); - let masterStub; + let primaryStub; - const reset = function() { + const reset = function () { outputCapture.flush(); expect(outputCapture.get()).to.equal(null); @@ -40,43 +40,48 @@ describe('Logging', () => { }; before((done) => { - masterStub = xmlrpc.createServer({host: 'localhost', port: MASTER_PORT}, () => { - rosnodejs.initNode('/testNode', { - rosMasterUri: `http://localhost:${MASTER_PORT}`, - logging: {skipRosLogging: true}, - notime: true - }) - .then(() => { - rosnodejs.log.addStream({ - type: 'raw', - level: 'info', - stream: outputCapture - }); - - rosnodejs.log.setLevel('trace'); - done(); - }); + primaryStub = xmlrpc.createServer( + { host: "localhost", port: PRIMARY_PORT }, + () => { + rosnodejs + .initNode("/testNode", { + rosPrimaryUri: `http://localhost:${PRIMARY_PORT}`, + logging: { skipRosLogging: true }, + notime: true, + }) + .then(() => { + rosnodejs.log.addStream({ + type: "raw", + level: "info", + stream: outputCapture, + }); + + rosnodejs.log.setLevel("trace"); + done(); + }); + } + ); + + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", `localhost:${PRIMARY_PORT}/`]; + callback(null, resp); }); - - masterStub.on('getUri', (err, params, callback) => { - const resp = [ 1, '', `localhost:${MASTER_PORT}/` ]; - callback(null, resp); - }); }); - after((done)=> { - rosnodejs.shutdown() - .then(() => { + after((done) => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); - masterStub.close(() => { done(); }); + primaryStub.close(() => { + done(); + }); }); }); - it('Levels', () => { - const message = 'This is my message'; + it("Levels", () => { + const message = "This is my message"; reset(); - rosnodejs.log.setLevel('fatal'); + rosnodejs.log.setLevel("fatal"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -96,7 +101,7 @@ describe('Logging', () => { expect(outputCapture.get()).to.equal(null); reset(); - rosnodejs.log.setLevel('error'); + rosnodejs.log.setLevel("error"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -116,7 +121,7 @@ describe('Logging', () => { expect(outputCapture.get()).to.equal(null); reset(); - rosnodejs.log.setLevel('warn'); + rosnodejs.log.setLevel("warn"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -136,7 +141,7 @@ describe('Logging', () => { expect(outputCapture.get()).to.equal(null); reset(); - rosnodejs.log.setLevel('info'); + rosnodejs.log.setLevel("info"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -156,7 +161,7 @@ describe('Logging', () => { expect(outputCapture.get()).to.equal(null); reset(); - rosnodejs.log.setLevel('debug'); + rosnodejs.log.setLevel("debug"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -176,7 +181,7 @@ describe('Logging', () => { expect(outputCapture.get()).to.equal(null); reset(); - rosnodejs.log.setLevel('trace'); + rosnodejs.log.setLevel("trace"); rosnodejs.log.fatal(message); expect(outputCapture.get().msg).to.have.string(message); reset(); @@ -197,8 +202,8 @@ describe('Logging', () => { reset(); }); - it('Throttling', () => { - const message = 'This is my message'; + it("Throttling", () => { + const message = "This is my message"; reset(); rosnodejs.log.infoThrottle(1000, message); expect(outputCapture.get().msg).to.have.string(message); @@ -209,8 +214,8 @@ describe('Logging', () => { expect(outputCapture.get()).to.be.null; }); - it('Bound Log Methods', () => { - const message = 'This is my message'; + it("Bound Log Methods", () => { + const message = "This is my message"; reset(); rosnodejs.log.trace(message); @@ -273,14 +278,14 @@ describe('Logging', () => { expect(outputCapture.get().level).to.equal(bunyan.FATAL); }); - it('Child Loggers', () => { - const message = 'This is my message'; + it("Child Loggers", () => { + const message = "This is my message"; - let testLogger = rosnodejs.log.getLogger('testLogger'); + let testLogger = rosnodejs.log.getLogger("testLogger"); // individually set log level reset(); - testLogger.setLevel('info'); + testLogger.setLevel("info"); testLogger.info(message); expect(outputCapture.get().msg).to.have.string(message); @@ -294,101 +299,108 @@ describe('Logging', () => { expect(outputCapture.get().msg).to.have.string(message); // setting through rosnodejs should set all loggers - rosnodejs.log.setLevel('trace'); + rosnodejs.log.setLevel("trace"); reset(); testLogger.trace(message); expect(outputCapture.get().msg).to.have.string(message); }); - describe('Rosout', () => { + describe("Rosout", () => { let pubInfo = null; let subInfo = null; before((done) => { - rosnodejs.shutdown() - .then(() => { - rosnodejs.reset(); - return rosnodejs.initNode('/testNode', {logging: {waitOnRosOut: false, level: 'info'}, - rosMasterUri: `http://localhost:${MASTER_PORT}`, notime: true}); - }) - .then(() => { - done(); - }); + rosnodejs + .shutdown() + .then(() => { + rosnodejs.reset(); + return rosnodejs.initNode("/testNode", { + logging: { waitOnRosOut: false, level: "info" }, + rosPrimaryUri: `http://localhost:${PRIMARY_PORT}`, + notime: true, + }); + }) + .then(() => { + done(); + }); - masterStub.on('getUri', (err, params, callback) => { - const resp = [ 1, '', `localhost:${MASTER_PORT}/` ]; + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", `localhost:${PRIMARY_PORT}/`]; callback(null, resp); }); - masterStub.on('registerSubscriber', (err, params, callback) => { + primaryStub.on("registerSubscriber", (err, params, callback) => { subInfo = params[3]; //console.log('sub reg ' + params); //console.log(pubInfo); - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (pubInfo) { resp[2].push(pubInfo); } callback(null, resp); }); - masterStub.on('unregisterSubscriber', (err, params, callback) => { - const resp = [1, 'You did it!', subInfo ? 1 : 0]; + primaryStub.on("unregisterSubscriber", (err, params, callback) => { + const resp = [1, "You did it!", subInfo ? 1 : 0]; callback(null, resp); subInfo = null; }); - masterStub.on('registerPublisher', (err, params, callback) => { + primaryStub.on("registerPublisher", (err, params, callback) => { //console.log('pub reg'); pubInfo = params[3]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (subInfo) { resp[2].push(pubInfo); - let subAddrParts = subInfo.replace('http://', '').split(':'); - let client = xmlrpc.createClient({host: subAddrParts[0], port: subAddrParts[1]}); + let subAddrParts = subInfo.replace("http://", "").split(":"); + let client = xmlrpc.createClient({ + host: subAddrParts[0], + port: subAddrParts[1], + }); let data = [1, topic, [pubInfo]]; - client.methodCall('publisherUpdate', data, (err, response) => { }); + client.methodCall("publisherUpdate", data, (err, response) => {}); } callback(null, resp); }); - masterStub.on('unregisterPublisher', (err, params, callback) => { - const resp = [1, 'You did it!', pubInfo ? 1 : 0]; + primaryStub.on("unregisterPublisher", (err, params, callback) => { + const resp = [1, "You did it!", pubInfo ? 1 : 0]; callback(null, resp); pubInfo = null; }); - masterStub.on('registerService', (err, params, callback) => { - const resp = [1, 'You did it!', 1]; + primaryStub.on("registerService", (err, params, callback) => { + const resp = [1, "You did it!", 1]; callback(null, resp); }); - masterStub.on('unregisterService', (err, params, callback) => { - const resp = [1, 'You did it!', 1]; + primaryStub.on("unregisterService", (err, params, callback) => { + const resp = [1, "You did it!", 1]; callback(null, resp); }); }); after(() => { - // remove any master api handlers we set up - masterStub.removeAllListeners(); + // remove any primary api handlers we set up + primaryStub.removeAllListeners(); }); - it('Check Publishing', (done) => { - rosnodejs.log.setLevel('fatal'); - const testLogger = rosnodejs.log.getLogger('testLogger'); - testLogger.setLevel('info'); + it("Check Publishing", (done) => { + rosnodejs.log.setLevel("fatal"); + const testLogger = rosnodejs.log.getLogger("testLogger"); + testLogger.setLevel("info"); const nh = rosnodejs.nh; - const message = 'This is my message'; + const message = "This is my message"; let intervalId = null; let timeout = setTimeout(() => { - throw new Error('Didn\'t receive log message within 500ms...'); + throw new Error("Didn't receive log message within 500ms..."); }, 500); const rosoutCallback = (msg) => { if (msg.msg.indexOf(message) > -1) { - nh.unsubscribe('/rosout'); + nh.unsubscribe("/rosout"); clearInterval(intervalId); clearTimeout(timeout); intervalId = null; @@ -396,12 +408,11 @@ describe('Logging', () => { } }; - const sub = nh.subscribe('/rosout', 'rosgraph_msgs/Log', rosoutCallback); + const sub = nh.subscribe("/rosout", "rosgraph_msgs/Log", rosoutCallback); intervalId = setInterval(() => { testLogger.info(message); }, 50); }); }); - }); diff --git a/test/namespaceTest.js b/test/namespaceTest.js index bde0326..e18e408 100644 --- a/test/namespaceTest.js +++ b/test/namespaceTest.js @@ -1,135 +1,138 @@ -'use strict'; +"use strict"; -const chai = require('chai'); +const chai = require("chai"); const expect = chai.expect; -const xmlrpc = require('xmlrpc'); -const names = require('../src/lib/Names.js'); -const NodeHandle = require('../src/lib/NodeHandle.js'); -const MasterStub = require('./utils/MasterStub.js'); -const rosnodejs = require('../src/index.js'); -const remapUtils = require('../src/utils/remapping_utils.js'); -const netUtils = require('../src/utils/network_utils.js'); - -describe('Namespace', function () { +const xmlrpc = require("xmlrpc"); +const names = require("../src/lib/Names.js"); +const NodeHandle = require("../src/lib/NodeHandle.js"); +const PrimaryStub = require("./utils/PrimaryStub.js"); +const rosnodejs = require("../src/index.js"); +const remapUtils = require("../src/utils/remapping_utils.js"); +const netUtils = require("../src/utils/network_utils.js"); + +describe("Namespace", function () { let nodeHandle; - names.init({}, '/namespace'); + names.init({}, "/namespace"); function _setupNodeHandle(name) { nodeHandle = new NodeHandle(null, name); - nodeHandle.getNodeName = function() { return '/test_node' }; + nodeHandle.getNodeName = function () { + return "/test_node"; + }; } - it('Validate', () => { + it("Validate", () => { expect(names.validate(null)).to.be.false; expect(names.validate()).to.be.false; expect(names.validate({})).to.be.false; expect(names.validate(1)).to.be.false; - expect(names.validate('/my-node')).to.be.false; + expect(names.validate("/my-node")).to.be.false; - expect(names.validate('')).to.be.true; - expect(names.validate('hi')).to.be.true; - expect(names.validate('/hi')).to.be.true; - expect(names.validate('~hi')).to.be.true; - expect(names.validate('~a_z09asdf')).to.be.true; + expect(names.validate("")).to.be.true; + expect(names.validate("hi")).to.be.true; + expect(names.validate("/hi")).to.be.true; + expect(names.validate("~hi")).to.be.true; + expect(names.validate("~a_z09asdf")).to.be.true; }); + describe("Resolving", () => { + it("Utils", () => { + expect(names.resolve("bar")).to.equal("/namespace/bar"); + expect(names.resolve("/bar")).to.equal("/bar"); + expect(names.resolve("~bar")).to.equal("/namespace/bar"); - describe('Resolving', () => { + expect(names.resolve("/scope_1", "bar")).to.equal("/scope_1/bar"); + expect(names.resolve("/scope_1", "/bar")).to.equal("/bar"); + expect(names.resolve("/scope_1", "~bar")).to.equal("/namespace/bar"); - it('Utils', () => { - expect(names.resolve('bar')).to.equal('/namespace/bar'); - expect(names.resolve('/bar')).to.equal('/bar'); - expect(names.resolve('~bar')).to.equal('/namespace/bar'); + names.init({}, "/"); + expect(names.resolve("bar")).to.equal("/bar"); + expect(names.resolve("/bar")).to.equal("/bar"); + expect(names.resolve("~bar")).to.equal("/bar"); - expect(names.resolve('/scope_1', 'bar')).to.equal('/scope_1/bar'); - expect(names.resolve('/scope_1', '/bar')).to.equal('/bar'); - expect(names.resolve('/scope_1', '~bar')).to.equal('/namespace/bar'); - - names.init({}, '/'); - expect(names.resolve('bar')).to.equal('/bar'); - expect(names.resolve('/bar')).to.equal('/bar'); - expect(names.resolve('~bar')).to.equal('/bar'); - - expect(names.resolve('/scope_1', 'bar')).to.equal('/scope_1/bar'); - expect(names.resolve('/scope_1', '/bar')).to.equal('/bar'); - expect(names.resolve('/scope_1', '~bar')).to.equal('/bar'); + expect(names.resolve("/scope_1", "bar")).to.equal("/scope_1/bar"); + expect(names.resolve("/scope_1", "/bar")).to.equal("/bar"); + expect(names.resolve("/scope_1", "~bar")).to.equal("/bar"); }); - it('Default Nodehandle', () => { - - names.init({}, '/'); + it("Default Nodehandle", () => { + names.init({}, "/"); _setupNodeHandle(); - expect(nodeHandle.resolveName('bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - names.init({}, '/scope'); + names.init({}, "/scope"); _setupNodeHandle(); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/scope/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); }); - it('Named Nodehandle', () => { - names.init({}, '/'); - _setupNodeHandle('/scope_1'); + it("Named Nodehandle", () => { + names.init({}, "/"); + _setupNodeHandle("/scope_1"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope_1/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/scope_1/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - names.init({}, '/'); - _setupNodeHandle('scope_1'); + names.init({}, "/"); + _setupNodeHandle("scope_1"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope_1/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/scope_1/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - names.init({}, '/sooop'); - _setupNodeHandle('/scope_1'); + names.init({}, "/sooop"); + _setupNodeHandle("/scope_1"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope_1/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/scope_1/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - names.init({}, '/sooop'); - _setupNodeHandle('scope_1'); + names.init({}, "/sooop"); + _setupNodeHandle("scope_1"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/sooop/scope_1/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal( + "/sooop/scope_1/bar" + ); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); }); - it('Private Nodehandle', () => { - names.init({}, '/scope'); - _setupNodeHandle('~'); + it("Private Nodehandle", () => { + names.init({}, "/scope"); + _setupNodeHandle("~"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/scope/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - _setupNodeHandle('~/subscope'); + _setupNodeHandle("~/subscope"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/scope/subscope/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal( + "/scope/subscope/bar" + ); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); - names.init({}, '/'); - _setupNodeHandle('~'); + names.init({}, "/"); + _setupNodeHandle("~"); - expect(nodeHandle.resolveName('bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName('/bar', false)).to.equal('/bar'); - expect(nodeHandle.resolveName.bind(nodeHandle, '~bar', false)).to.throw(); + expect(nodeHandle.resolveName("bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName("/bar", false)).to.equal("/bar"); + expect(nodeHandle.resolveName.bind(nodeHandle, "~bar", false)).to.throw(); }); }); - describe('with ros', () => { - const MASTER_PORT = 12342; - const rosMasterUri = `http://localhost:${MASTER_PORT}`; - let masterStub = new MasterStub('localhost', MASTER_PORT); - masterStub.provideAll(); + describe("with ros", () => { + const PRIMARY_PORT = 12342; + const rosPrimaryUri = `http://localhost:${PRIMARY_PORT}`; + let primaryStub = new PrimaryStub("localhost", PRIMARY_PORT); + primaryStub.provideAll(); const ARGV_LEN = process.argv.length; function resetArgv() { @@ -141,17 +144,15 @@ describe('Namespace', function () { } after((done) => { - masterStub.shutdown() - .then(() => { + primaryStub.shutdown().then(() => { done(); }); - }) + }); afterEach((done) => { resetArgv(); - rosnodejs.shutdown() - .then(() => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); done(); }); @@ -159,135 +160,134 @@ describe('Namespace', function () { // test special key remapping // wiki.ros.org/Remapping Arguments - it('__name', function(done) { + it("__name", function (done) { this.slow(500); - const remappedName = 'custom_name'; + const remappedName = "custom_name"; setRemapArg(remapUtils.SPECIAL_KEYS.name, remappedName); - rosnodejs.initNode('node_name', { rosMasterUri }) - .then(() => { - expect(rosnodejs.nh.getNodeName()).to.equal('/' + remappedName); + rosnodejs.initNode("node_name", { rosPrimaryUri }).then(() => { + expect(rosnodejs.nh.getNodeName()).to.equal("/" + remappedName); done(); }); }); - it('__ip', function(done) { + it("__ip", function (done) { this.slow(500); - const remappedIp = '1.2.3.4'; + const remappedIp = "1.2.3.4"; setRemapArg(remapUtils.SPECIAL_KEYS.ip, remappedIp); - rosnodejs.initNode('node_name', { rosMasterUri }) - .then(() => { + rosnodejs.initNode("node_name", { rosPrimaryUri }).then(() => { expect(netUtils.getHost()).to.equal(remappedIp); done(); }); }); - it('__hostname', function(done) { + it("__hostname", function (done) { this.slow(500); - const remappedHost = 'customHost'; + const remappedHost = "customHost"; setRemapArg(remapUtils.SPECIAL_KEYS.hostname, remappedHost); - rosnodejs.initNode('node_name', { rosMasterUri }) - .then(() => { + rosnodejs.initNode("node_name", { rosPrimaryUri }).then(() => { expect(netUtils.getHost()).to.equal(remappedHost); done(); }); }); - it('__master', function(done) { + it("__primary", function (done) { this.slow(500); - const CUSTOM_MASTER_PORT = 12355; - const rosMasterUri = `http://localhost:${CUSTOM_MASTER_PORT}`; - let masterStub = new MasterStub('localhost', CUSTOM_MASTER_PORT); - masterStub.provideAll(); - - const remappedMaster = `http://localhost:${CUSTOM_MASTER_PORT}`; - setRemapArg(remapUtils.SPECIAL_KEYS.master, remappedMaster); - - masterStub.once('ready', function() { - rosnodejs.initNode('node_name', { rosMasterUri }) - .then(() => { - expect(rosnodejs.nh._node.getRosMasterUri()).to.equal(remappedMaster); - - // shutdown rosnodejs here since we're also killing our custom master stub - return rosnodejs.shutdown() - }) - .then(() => { - return masterStub.shutdown() - }) - .then(() => { - done(); - }); + const CUSTOM_PRIMARY_PORT = 12355; + const rosPrimaryUri = `http://localhost:${CUSTOM_PRIMARY_PORT}`; + let primaryStub = new PrimaryStub("localhost", CUSTOM_PRIMARY_PORT); + primaryStub.provideAll(); + + const remappedPrimary = `http://localhost:${CUSTOM_PRIMARY_PORT}`; + setRemapArg(remapUtils.SPECIAL_KEYS.primary, remappedPrimary); + + primaryStub.once("ready", function () { + rosnodejs + .initNode("node_name", { rosPrimaryUri }) + .then(() => { + expect(rosnodejs.nh._node.getRosPrimaryUri()).to.equal( + remappedPrimary + ); + + // shutdown rosnodejs here since we're also killing our custom primary stub + return rosnodejs.shutdown(); + }) + .then(() => { + return primaryStub.shutdown(); + }) + .then(() => { + done(); + }); }); }); - it('__ns', function() { + it("__ns", function () { this.slow(500); - const remappedNs = 'customNs'; + const remappedNs = "customNs"; setRemapArg(remapUtils.SPECIAL_KEYS.ns, remappedNs); - const nodeName = 'node_name'; - return rosnodejs.initNode(nodeName, { rosMasterUri }) - .then(() => { - expect(rosnodejs.nh.getNodeName()).to.equal(`/${remappedNs}/${nodeName}`); + const nodeName = "node_name"; + return rosnodejs.initNode(nodeName, { rosPrimaryUri }).then(() => { + expect(rosnodejs.nh.getNodeName()).to.equal( + `/${remappedNs}/${nodeName}` + ); // make sure re-initing the same node still works - return rosnodejs.initNode(nodeName, { rosMasterUri }) - .then(() => { - expect(rosnodejs.nh.getNodeName()).to.equal(`/${remappedNs}/${nodeName}`); + return rosnodejs.initNode(nodeName, { rosPrimaryUri }).then(() => { + expect(rosnodejs.nh.getNodeName()).to.equal( + `/${remappedNs}/${nodeName}` + ); }); }); }); - it('Re-init Without Remapping', function() { + it("Re-init Without Remapping", function () { this.slow(500); - const nodeName = 'node_name'; - return rosnodejs.initNode(nodeName, { rosMasterUri }) - .then(() => { + const nodeName = "node_name"; + return rosnodejs.initNode(nodeName, { rosPrimaryUri }).then(() => { expect(rosnodejs.nh.getNodeName()).to.equal(`/${nodeName}`); // make sure re-initing the same node still works - return rosnodejs.initNode(nodeName, { rosMasterUri }) - .then(() => { + return rosnodejs.initNode(nodeName, { rosPrimaryUri }).then(() => { expect(rosnodejs.nh.getNodeName()).to.equal(`/${nodeName}`); }); }); }); - it('comms', function(done) { + it("comms", function (done) { this.slow(500); - const topic = '/base/topic'; - const remappedTopic = '/newBase/topic'; - const service = '/base/service'; - const remappedService = '/newBase/service'; - const param = '/base/param'; - const remappedParam = '/newBase/param'; + const topic = "/base/topic"; + const remappedTopic = "/newBase/topic"; + const service = "/base/service"; + const remappedService = "/newBase/service"; + const param = "/base/param"; + const remappedParam = "/newBase/param"; setRemapArg(topic, remappedTopic); setRemapArg(service, remappedService); setRemapArg(param, remappedParam); - rosnodejs.initNode('node_name', { rosMasterUri }) - .then((nh) => { - const pub = nh.advertise(topic, 'std_msgs/Empty'); + rosnodejs.initNode("node_name", { rosPrimaryUri }).then((nh) => { + const pub = nh.advertise(topic, "std_msgs/Empty"); expect(pub.getTopic()).to.equal(remappedTopic); - const sub = nh.subscribe(topic, 'std_msgs/Empty'); + const sub = nh.subscribe(topic, "std_msgs/Empty"); expect(sub.getTopic()).to.equal(remappedTopic); - const srv = nh.advertiseService(service, 'std_srvs/Empty'); + const srv = nh.advertiseService(service, "std_srvs/Empty"); expect(srv.getService()).to.equal(remappedService); - const srvClient = nh.serviceClient(service, 'std_srvs/Empty'); + const srvClient = nh.serviceClient(service, "std_srvs/Empty"); expect(srvClient.getService()).to.equal(remappedService); let outstandingParamCalls = 4; @@ -297,18 +297,17 @@ describe('Namespace', function () { --outstandingParamCalls; } - masterStub.once('setParam', paramTest); - masterStub.once('getParam', paramTest); - masterStub.once('hasParam', paramTest); - masterStub.once('deleteParam', paramTest); + primaryStub.once("setParam", paramTest); + primaryStub.once("getParam", paramTest); + primaryStub.once("hasParam", paramTest); + primaryStub.once("deleteParam", paramTest); Promise.all([ nh.setParam(param, 2), nh.getParam(param, 2), nh.hasParam(param, 2), - nh.deleteParam(param, 2) - ]) - .then(() => { + nh.deleteParam(param, 2), + ]).then(() => { if (outstandingParamCalls <= 0) { done(); } @@ -316,58 +315,56 @@ describe('Namespace', function () { }); }); - it('comms namespace', function(done) { + it("comms namespace", function (done) { this.slow(500); - const nodeName = 'node_name'; - const topic = 'topic'; + const nodeName = "node_name"; + const topic = "topic"; const remappedTopic = `/${nodeName}/topic`; - const service = 'service'; + const service = "service"; const remappedService = `/${nodeName}/service`; - const param = 'param'; + const param = "param"; const remappedParam = `/${nodeName}/param`; setRemapArg(topic, remappedTopic); setRemapArg(service, remappedService); setRemapArg(param, remappedParam); - rosnodejs.initNode(nodeName, { rosMasterUri }) - .then((nh) => { - const pub = nh.advertise(topic, 'std_msgs/Empty'); - expect(pub.getTopic()).to.equal(remappedTopic); + rosnodejs.initNode(nodeName, { rosPrimaryUri }).then((nh) => { + const pub = nh.advertise(topic, "std_msgs/Empty"); + expect(pub.getTopic()).to.equal(remappedTopic); + + const sub = nh.subscribe(topic, "std_msgs/Empty"); + expect(sub.getTopic()).to.equal(remappedTopic); + + const srv = nh.advertiseService(service, "std_srvs/Empty"); + expect(srv.getService()).to.equal(remappedService); - const sub = nh.subscribe(topic, 'std_msgs/Empty'); - expect(sub.getTopic()).to.equal(remappedTopic); + const srvClient = nh.serviceClient(service, "std_srvs/Empty"); + expect(srvClient.getService()).to.equal(remappedService); - const srv = nh.advertiseService(service, 'std_srvs/Empty'); - expect(srv.getService()).to.equal(remappedService); + let outstandingParamCalls = 4; - const srvClient = nh.serviceClient(service, 'std_srvs/Empty'); - expect(srvClient.getService()).to.equal(remappedService); + function paramTest(err, params) { + expect(params[1]).to.equal(remappedParam); + --outstandingParamCalls; + } - let outstandingParamCalls = 4; + primaryStub.once("setParam", paramTest); + primaryStub.once("getParam", paramTest); + primaryStub.once("hasParam", paramTest); + primaryStub.once("deleteParam", paramTest); - function paramTest(err, params) { - expect(params[1]).to.equal(remappedParam); - --outstandingParamCalls; + Promise.all([ + nh.setParam(param, 2), + nh.getParam(param, 2), + nh.hasParam(param, 2), + nh.deleteParam(param, 2), + ]).then(() => { + if (outstandingParamCalls <= 0) { + done(); } - - masterStub.once('setParam', paramTest); - masterStub.once('getParam', paramTest); - masterStub.once('hasParam', paramTest); - masterStub.once('deleteParam', paramTest); - - Promise.all([ - nh.setParam(param, 2), - nh.getParam(param, 2), - nh.hasParam(param, 2), - nh.deleteParam(param, 2) - ]) - .then(() => { - if (outstandingParamCalls <= 0) { - done(); - } - }); }); + }); }); }); }); diff --git a/test/onTheFly.js b/test/onTheFly.js index a747a6f..3dc136a 100644 --- a/test/onTheFly.js +++ b/test/onTheFly.js @@ -1,66 +1,99 @@ -'use strict'; +"use strict"; -const chai = require('chai'); +const chai = require("chai"); const expect = chai.expect; -const xmlrpc = require('xmlrpc'); -const rosnodejs = require('../src/index.js'); -const Master = require('./utils/MasterStub.js'); +const xmlrpc = require("xmlrpc"); +const rosnodejs = require("../src/index.js"); +const Primary = require("./utils/PrimaryStub.js"); -const MASTER_PORT = 11234; +const PRIMARY_PORT = 11234; -describe('OnTheFly', function () { - let master; +describe("OnTheFly", function () { + let primary; - before(function() { + before(function () { this.timeout(0); - master = new Master('localhost', MASTER_PORT); - master.provideAll(); + primary = new Primary("localhost", PRIMARY_PORT); + primary.provideAll(); - return rosnodejs.initNode('/testNode', { - rosMasterUri: `http://localhost:${MASTER_PORT}`, + return rosnodejs.initNode("/testNode", { + rosPrimaryUri: `http://localhost:${PRIMARY_PORT}`, onTheFly: true, notime: true, - logging: {skipRosLogging: true}}) + logging: { skipRosLogging: true }, + }); }); after(() => { rosnodejs.reset(); - return master.shutdown(); + return primary.shutdown(); }); - it('serialize/deserialize PoseWithCovariance', (done) => { - const geometry_msgs = rosnodejs.require('geometry_msgs').msg; + it("serialize/deserialize PoseWithCovariance", (done) => { + const geometry_msgs = rosnodejs.require("geometry_msgs").msg; const msg = new geometry_msgs.PoseWithCovariance({ - pose: { - position: {x:0, y:0, z:0}, - orientation: {w:1, x:0, y:0, z:0} - }, - covariance: [ - 0,0,0,0,0,0.123, - 0,2,0,0,0,0, - 0,0,4,0,0,0, - 0,0,0,6,0,0, - 0,0,0,0,8,0, - 0.123,0,0,0,0,0.654321654321 - ] - }); + pose: { + position: { x: 0, y: 0, z: 0 }, + orientation: { w: 1, x: 0, y: 0, z: 0 }, + }, + covariance: [ + 0, + 0, + 0, + 0, + 0, + 0.123, + 0, + 2, + 0, + 0, + 0, + 0, + 0, + 0, + 4, + 0, + 0, + 0, + 0, + 0, + 0, + 6, + 0, + 0, + 0, + 0, + 0, + 0, + 8, + 0, + 0.123, + 0, + 0, + 0, + 0, + 0.654321654321, + ], + }); const size = geometry_msgs.PoseWithCovariance.getMessageSize(msg); const buffer = new Buffer(size); geometry_msgs.PoseWithCovariance.serialize(msg, buffer, 0); const read = geometry_msgs.PoseWithCovariance.deserialize(buffer); - expect(read.covariance.length == msg.covariance.length - && read.covariance.every((v,i)=> v === msg.covariance[i])).to.be.true; + expect( + read.covariance.length == msg.covariance.length && + read.covariance.every((v, i) => v === msg.covariance[i]) + ).to.be.true; done(); }); - it('serialize/deserialize String', (done) => { - const std_msgs = rosnodejs.require('std_msgs').msg; - const data = 'sДvΣ τhΣ 子猫'; // Test with multi-byte UTF-8 characters. - // If this test fails, you killed a kitten. + it("serialize/deserialize String", (done) => { + const std_msgs = rosnodejs.require("std_msgs").msg; + const data = "sДvΣ τhΣ 子猫"; // Test with multi-byte UTF-8 characters. + // If this test fails, you killed a kitten. const msg = new std_msgs.String({ data: data }); const size = std_msgs.String.getMessageSize(msg); diff --git a/test/stress.js b/test/stress.js index 72a13e0..164ed14 100644 --- a/test/stress.js +++ b/test/stress.js @@ -1,19 +1,17 @@ +const chai = require("chai"); +const xmlrpc = require("xmlrpc"); +const rosnodejs = require("rosnodejs"); -const chai = require('chai'); -const xmlrpc = require('xmlrpc'); -const rosnodejs = require('rosnodejs'); +const TOPIC = "/topic"; +const TYPE = "std_msgs/String"; +const SERVICE = "/service"; +const SRV = "std_srvs/Empty"; -const TOPIC = '/topic'; -const TYPE = 'std_msgs/String'; -const SERVICE = '/service'; -const SRV = 'std_srvs/Empty'; - -const MASTER_PORT = 11234; +const PRIMARY_PORT = 11234; // Each Test in this suite simulates rapid fire connection/disconnection // of TCPROS clients -describe('ClientShutdown', function() { - +describe("ClientShutdown", function () { this.timeout(10000); this.slow(10000); @@ -26,11 +24,11 @@ describe('ClientShutdown', function() { let interval2; let interval3; - let masterStub; + let primaryStub; function startSub(nh) { sub = nh.subscribe(TOPIC, TYPE, (msg) => { - console.log('%j', msg); + console.log("%j", msg); }); return sub; @@ -57,7 +55,7 @@ describe('ClientShutdown', function() { function startService(nh) { service = nh.advertiseService(SERVICE, SRV, () => { - console.log('handling service call'); + console.log("handling service call"); return true; }); return service; @@ -83,11 +81,18 @@ describe('ClientShutdown', function() { } before((done) => { - masterStub = xmlrpc.createServer({host: 'localhost', port: MASTER_PORT}, () => { done(); }); + primaryStub = xmlrpc.createServer( + { host: "localhost", port: PRIMARY_PORT }, + () => { + done(); + } + ); }); after((done) => { - masterStub.close(() => { done(); }); + primaryStub.close(() => { + done(); + }); }); beforeEach(() => { @@ -95,86 +100,95 @@ describe('ClientShutdown', function() { let subInfo = null; let serviceInfo = null; - masterStub.on('getUri', (err, params, callback) => { - const resp = [ 1, '', 'localhost:11311/' ]; + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", "localhost:11311/"]; callback(null, resp); }); - masterStub.on('registerSubscriber', (err, params, callback) => { + primaryStub.on("registerSubscriber", (err, params, callback) => { subInfo = params[3]; // console.log('sub reg ' + params); //console.log(pubInfo); - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (pubInfo) { resp[2].push(pubInfo); } callback(null, resp); }); - masterStub.on('unregisterSubscriber', (err, params, callback) => { + primaryStub.on("unregisterSubscriber", (err, params, callback) => { // console.log('unregister subscriber!'); - const resp = [1, 'You did it!', subInfo ? 1 : 0]; + const resp = [1, "You did it!", subInfo ? 1 : 0]; callback(null, resp); subInfo = null; }); - masterStub.on('registerPublisher', (err, params, callback) => { + primaryStub.on("registerPublisher", (err, params, callback) => { // console.log('pub reg ' + Date.now()); pubInfo = params[3]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (subInfo) { resp[2].push(pubInfo); - let subAddrParts = subInfo.replace('http://', '').split(':'); - let client = xmlrpc.createClient({host: subAddrParts[0], port: subAddrParts[1]}); + let subAddrParts = subInfo.replace("http://", "").split(":"); + let client = xmlrpc.createClient({ + host: subAddrParts[0], + port: subAddrParts[1], + }); let data = [1, TOPIC, [pubInfo]]; - client.methodCall('publisherUpdate', data, (err, response) => { }); + client.methodCall("publisherUpdate", data, (err, response) => {}); } callback(null, resp); }); - masterStub.on('unregisterPublisher', (err, params, callback) => { + primaryStub.on("unregisterPublisher", (err, params, callback) => { // console.log('pub unreg ' + Date.now()); - const resp = [1, 'You did it!', pubInfo ? 1 : 0]; + const resp = [1, "You did it!", pubInfo ? 1 : 0]; callback(null, resp); if (subInfo) { - let subAddrParts = subInfo.replace('http://', '').split(':'); - let client = xmlrpc.createClient({host: subAddrParts[0], port: subAddrParts[1]}); + let subAddrParts = subInfo.replace("http://", "").split(":"); + let client = xmlrpc.createClient({ + host: subAddrParts[0], + port: subAddrParts[1], + }); let data = [1, TOPIC, []]; - client.methodCall('publisherUpdate', data, (err, response) => { }); + client.methodCall("publisherUpdate", data, (err, response) => {}); } pubInfo = null; }); - masterStub.on('registerService', (err, params, callback) => { + primaryStub.on("registerService", (err, params, callback) => { serviceInfo = params[2]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; callback(null, resp); }); - masterStub.on('unregisterService', (err, params, callback) => { - const resp = [1, 'You did it!', subInfo ? 1 : 0]; + primaryStub.on("unregisterService", (err, params, callback) => { + const resp = [1, "You did it!", subInfo ? 1 : 0]; callback(null, resp); serviceInfo = null; }); - masterStub.on('lookupService', (err, params, callback) => { + primaryStub.on("lookupService", (err, params, callback) => { if (serviceInfo) { const resp = [1, "you did it", serviceInfo]; callback(null, resp); - } - else { + } else { const resp = [-1, "no provider", ""]; callback(null, resp); } }); - masterStub.on('NotFound', (method, params) => { - console.error('Got unknown method call %s: %j', method, params); + primaryStub.on("NotFound", (method, params) => { + console.error("Got unknown method call %s: %j", method, params); }); - return rosnodejs.initNode('/my_node', {rosMasterUri: `http://localhost:${MASTER_PORT}`, logging: {testing: true}, notime:true}); + return rosnodejs.initNode("/my_node", { + rosPrimaryUri: `http://localhost:${PRIMARY_PORT}`, + logging: { testing: true }, + notime: true, + }); }); afterEach(() => { @@ -194,15 +208,15 @@ describe('ClientShutdown', function() { nh._node._subscribers = {}; nh._node._publishers = {}; - // remove any master api handlers we set up - masterStub.removeAllListeners(); + // remove any primary api handlers we set up + primaryStub.removeAllListeners(); }); - it('Subscriber Shutdown', (done) => { + it("Subscriber Shutdown", (done) => { const nh = rosnodejs.nh; const pub = startPub(nh); - const msg = {data: 'This shouldn\'t crash'}; + const msg = { data: "This shouldn't crash" }; interval1 = setInterval(() => { pub.publish(msg); @@ -211,8 +225,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (sub === null) { startSub(nh); - } - else { + } else { stopSub(); } }, 10); @@ -220,11 +233,11 @@ describe('ClientShutdown', function() { setTimeout(done, 8000); }); - it('Publisher Shutdown', (done) => { + it("Publisher Shutdown", (done) => { const nh = rosnodejs.nh; startSub(nh); - const msg = {data: 'This shouldn\'t crash'}; + const msg = { data: "This shouldn't crash" }; interval1 = setInterval(() => { if (pub) { @@ -235,8 +248,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (pub === null) { startPub(nh); - } - else { + } else { stopPub(); } }, 10); @@ -244,10 +256,10 @@ describe('ClientShutdown', function() { setTimeout(done, 8000); }); - it('Pub Sub Shutdown', (done) => { + it("Pub Sub Shutdown", (done) => { const nh = rosnodejs.nh; - const msg = {data: 'This shouldn\'t crash'}; + const msg = { data: "This shouldn't crash" }; interval1 = setInterval(() => { if (pub) { @@ -258,8 +270,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (pub === null) { startPub(nh); - } - else { + } else { stopPub(); } }, 10); @@ -267,8 +278,7 @@ describe('ClientShutdown', function() { interval3 = setInterval(() => { if (sub === null) { startSub(nh); - } - else { + } else { stopSub(); } }, 7); @@ -276,7 +286,7 @@ describe('ClientShutdown', function() { setTimeout(done, 8000); }); - it('Service Shutdown', (done) => { + it("Service Shutdown", (done) => { const nh = rosnodejs.nh; const client = startClient(nh); @@ -289,8 +299,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (service === null) { startService(nh); - } - else { + } else { stopService(); } }, 10); @@ -298,7 +307,7 @@ describe('ClientShutdown', function() { setTimeout(done, 8000); }); - it('Client Shutdown', (done) => { + it("Client Shutdown", (done) => { const nh = rosnodejs.nh; startService(nh); @@ -313,8 +322,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (client === null) { startClient(nh); - } - else { + } else { stopClient(); } }, 10); @@ -322,7 +330,7 @@ describe('ClientShutdown', function() { setTimeout(done, 8000); }); - it('Client Service Shutdown', (done) => { + it("Client Service Shutdown", (done) => { const nh = rosnodejs.nh; const req = {}; @@ -336,8 +344,7 @@ describe('ClientShutdown', function() { interval2 = setInterval(() => { if (client === null) { startClient(nh); - } - else { + } else { stopClient(); } }, 10); @@ -345,13 +352,11 @@ describe('ClientShutdown', function() { interval3 = setInterval(() => { if (service === null) { startService(nh); - } - else { + } else { stopService(); } }, 7); setTimeout(done, 8000); }); - }); diff --git a/test/utils/MasterStub.js b/test/utils/MasterStub.js index 34df5bc..240564f 100644 --- a/test/utils/MasterStub.js +++ b/test/utils/MasterStub.js @@ -1,7 +1,7 @@ -const xmlrpc = require('xmlrpc'); -const EventEmitter = require('events').EventEmitter; +const xmlrpc = require("xmlrpc"); +const EventEmitter = require("events").EventEmitter; -class RosMasterStub extends EventEmitter { +class RosPrimaryStub extends EventEmitter { constructor(host, port) { super(); @@ -21,7 +21,7 @@ class RosMasterStub extends EventEmitter { setParam: this._setParam.bind(this), getParam: this._getParam.bind(this), hasParam: this._hasParam.bind(this), - getParamNames: this._getParamNames.bind(this) + getParamNames: this._getParamNames.bind(this), }; this._providedApis = new Set(); @@ -29,7 +29,7 @@ class RosMasterStub extends EventEmitter { this._clientCache = { service: null, sub: null, - pub: null + pub: null, }; this._params = {}; @@ -40,13 +40,16 @@ class RosMasterStub extends EventEmitter { } listen() { - this._server = xmlrpc.createServer({host: this._host, port: this._port}, () => { - this.emit('ready'); - }); + this._server = xmlrpc.createServer( + { host: this._host, port: this._port }, + () => { + this.emit("ready"); + } + ); - this._server.on('NotFound', (method, params) => { + this._server.on("NotFound", (method, params) => { if (this.verbose) { - console.error('Method %s does not exist', method); + console.error("Method %s does not exist", method); } }); } @@ -79,24 +82,24 @@ class RosMasterStub extends EventEmitter { } _onGetUri(err, params, callback) { - const resp = [ 1, '', `${this._host}:${this._port}`]; + const resp = [1, "", `${this._host}:${this._port}`]; callback(null, resp); } _onGetParam(err, params, callback) { - const resp = [0, '', 'Not implemented in stub']; + const resp = [0, "", "Not implemented in stub"]; callback(null, resp); } _onRegisterService(err, params, callback) { this._clientCache.service = params[2]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; callback(null, resp); } _onUnregisterService(err, params, callback) { - const resp = [1, 'You did it!', this._clientCache.service ? 1 : 0]; + const resp = [1, "You did it!", this._clientCache.service ? 1 : 0]; callback(null, resp); this._clientCache.service = null; } @@ -106,8 +109,7 @@ class RosMasterStub extends EventEmitter { if (service) { const resp = [1, "you did it", service]; callback(null, resp); - } - else { + } else { const resp = [-1, "no provider", ""]; callback(null, resp); } @@ -116,7 +118,7 @@ class RosMasterStub extends EventEmitter { _onRegisterSubscriber(err, params, callback) { this._clientCache.sub = params[3]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (this._clientCache.pub) { resp[2].push(this._clientCache.pub); } @@ -124,7 +126,7 @@ class RosMasterStub extends EventEmitter { } _onUnregisterSubscriber(err, params, callback) { - const resp = [1, 'You did it!', this._clientCache.sub ? 1 : 0]; + const resp = [1, "You did it!", this._clientCache.sub ? 1 : 0]; callback(null, resp); this._clientCache.sub = null; } @@ -133,19 +135,24 @@ class RosMasterStub extends EventEmitter { const pubInfo = params[3]; this._clientCache.pub = pubInfo; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (this._clientCache.sub) { resp[2].push(pubInfo); - let subAddrParts = this._clientCache.sub.replace('http://', '').split(':'); - let client = xmlrpc.createClient({host: subAddrParts[0], port: subAddrParts[1]}); + let subAddrParts = this._clientCache.sub + .replace("http://", "") + .split(":"); + let client = xmlrpc.createClient({ + host: subAddrParts[0], + port: subAddrParts[1], + }); let data = [1, topic, [pubInfo]]; - client.methodCall('publisherUpdate', data, (err, response) => { }); + client.methodCall("publisherUpdate", data, (err, response) => {}); } callback(null, resp); } _onUnregisterPublisher(err, params, callback) { - const resp = [1, 'You did it!', this._clientCache.pub ? 1 : 0]; + const resp = [1, "You did it!", this._clientCache.pub ? 1 : 0]; callback(null, resp); this._clientCache.pub = null; } @@ -158,11 +165,10 @@ class RosMasterStub extends EventEmitter { const key = params[1]; if (this._params.hasOwnProperty(key)) { delete this._params[key]; - const resp = [1, 'delete value for ' + key, 1]; + const resp = [1, "delete value for " + key, 1]; callback(null, resp); - } - else { - const resp = [0, 'no value for ' + key, 1]; + } else { + const resp = [0, "no value for " + key, 1]; callback(null, resp); } } @@ -171,7 +177,7 @@ class RosMasterStub extends EventEmitter { const key = params[1]; const val = params[2]; this._params[key] = val; - const resp = [1, 'set value for ' + key, 1]; + const resp = [1, "set value for " + key, 1]; callback(null, resp); } @@ -179,26 +185,25 @@ class RosMasterStub extends EventEmitter { const key = params[1]; const val = this._params[key]; if (val !== undefined) { - const resp = [1, 'data for ' + key, val]; + const resp = [1, "data for " + key, val]; callback(null, resp); - } - else { - const resp = [0, 'no data for ' + key, null]; + } else { + const resp = [0, "no data for " + key, null]; callback(null, resp); } } _hasParam(err, params, callback) { const key = params[1]; - const resp = [1, 'check param ' + key, this._params.hasOwnProperty(key)]; + const resp = [1, "check param " + key, this._params.hasOwnProperty(key)]; callback(null, resp); } _getParamNames(err, params, callback) { const names = Object.keys(this._params); - const resp = [1, 'get param names', names]; + const resp = [1, "get param names", names]; callback(null, resp); } } -module.exports = RosMasterStub; +module.exports = RosPrimaryStub; diff --git a/test/xmlrpcTest.js b/test/xmlrpcTest.js index e5e722c..b72809f 100644 --- a/test/xmlrpcTest.js +++ b/test/xmlrpcTest.js @@ -1,41 +1,50 @@ -'use strict' +"use strict"; -const net = require('net'); -const chai = require('chai'); +const net = require("net"); +const chai = require("chai"); const expect = chai.expect; -const rosnodejs = require('../src/index.js'); -const Subscriber = require('../src/lib/Subscriber.js'); -const SubscriberImpl = require('../src/lib/impl/SubscriberImpl.js'); -const xmlrpc = require('xmlrpc'); -const netUtils = require('../src/utils/network_utils.js'); -const MasterStub = require('./utils/MasterStub.js'); +const rosnodejs = require("../src/index.js"); +const Subscriber = require("../src/lib/Subscriber.js"); +const SubscriberImpl = require("../src/lib/impl/SubscriberImpl.js"); +const xmlrpc = require("xmlrpc"); +const netUtils = require("../src/utils/network_utils.js"); +const PrimaryStub = require("./utils/PrimaryStub.js"); -const MASTER_PORT = 11234; +const PRIMARY_PORT = 11234; // helper function to throw errors outside a promise scope // so they actually trigger failures function throwNext(msg) { - process.nextTick(() => { throw new Error(msg)}); + process.nextTick(() => { + throw new Error(msg); + }); } -describe('Protocol Test', () => { +describe("Protocol Test", () => { // NOTE: make sure a roscore is not running (or something else at this address) - rosnodejs.require('std_msgs'); - rosnodejs.require('std_srvs'); - let masterStub; + rosnodejs.require("std_msgs"); + rosnodejs.require("std_srvs"); + let primaryStub; const initArgs = { - rosMasterUri: `http://localhost:${MASTER_PORT}`, - logging: {skipRosLogging: true}, - notime: true + rosPrimaryUri: `http://localhost:${PRIMARY_PORT}`, + logging: { skipRosLogging: true }, + notime: true, }; - const nodeName = '/testNode'; + const nodeName = "/testNode"; - function startMasterStub(done) { - masterStub = xmlrpc.createServer({host: 'localhost', port: MASTER_PORT}, () => { done(); }); + function startPrimaryStub(done) { + primaryStub = xmlrpc.createServer( + { host: "localhost", port: PRIMARY_PORT }, + () => { + done(); + } + ); } - function stopMasterStub(done) { - masterStub.close(() => { done(); }); + function stopPrimaryStub(done) { + primaryStub.close(() => { + done(); + }); } function clearOutClients(node) { @@ -57,30 +66,28 @@ describe('Protocol Test', () => { } before((done) => { - startMasterStub(() => { - rosnodejs.initNode(nodeName, initArgs) - .then(() => { - done() + startPrimaryStub(() => { + rosnodejs.initNode(nodeName, initArgs).then(() => { + done(); }); }); - masterStub.on('getUri', (err, params, callback) => { - const resp = [ 1, '', `localhost:${MASTER_PORT}/` ]; + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", `localhost:${PRIMARY_PORT}/`]; callback(null, resp); }); }); after((done) => { - stopMasterStub(() => { - rosnodejs.shutdown() - .then(() => { + stopPrimaryStub(() => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); done(); - }) + }); }); }); - describe('Xmlrpc', () => { + describe("Xmlrpc", () => { afterEach(() => { const nh = rosnodejs.nh; @@ -89,187 +96,189 @@ describe('Protocol Test', () => { nh._node._spinner.clear(); - // remove any master api handlers we set up - masterStub.removeAllListeners(); + // remove any primary api handlers we set up + primaryStub.removeAllListeners(); }); - it('registerSubscriber', (done) => { - const topic = '/test_topic'; - const msgType = 'std_msgs/String'; - masterStub.on('registerSubscriber', (err, params, callback) => { + it("registerSubscriber", (done) => { + const topic = "/test_topic"; + const msgType = "std_msgs/String"; + primaryStub.on("registerSubscriber", (err, params, callback) => { expect(params.length).to.equal(4); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(topic); expect(params[2]).to.equal(msgType); - expect(params[3].startsWith('http://')).to.be.true; + expect(params[3].startsWith("http://")).to.be.true; const info = netUtils.getAddressAndPortFromUri(params[3]); - expect(info.host).to.be.a('string'); + expect(info.host).to.be.a("string"); expect(info.host.length).to.not.equal(0); - expect(info.port).to.be.a('string'); + expect(info.port).to.be.a("string"); expect(info.port.length).to.not.equal(0); - const resp = [ 1, 'registered!', [] ]; + const resp = [1, "registered!", []]; callback(null, resp); }); const nh = rosnodejs.nh; - const sub = nh.subscribe(topic, msgType, - (data) => {}, - { queueSize: 1, throttleMs: 1000 } - ); + const sub = nh.subscribe(topic, msgType, (data) => {}, { + queueSize: 1, + throttleMs: 1000, + }); - sub.on('registered', () => { + sub.on("registered", () => { done(); - }) + }); }); - it('unregisterSubscriber', (done) => { - const topic = '/test_topic'; - const msgType = 'std_msgs/String'; + it("unregisterSubscriber", (done) => { + const topic = "/test_topic"; + const msgType = "std_msgs/String"; let nodeUri; - masterStub.on('registerSubscriber', (err, params, callback) => { + primaryStub.on("registerSubscriber", (err, params, callback) => { nodeUri = params[3]; - const resp = [ 1, 'registered!', [] ]; + const resp = [1, "registered!", []]; callback(null, resp); }); - masterStub.on('unregisterSubscriber', (err, params, callback) => { + primaryStub.on("unregisterSubscriber", (err, params, callback) => { expect(params.length).to.equal(3); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(topic); expect(params[2]).to.equal(nodeUri); - const resp = [ 1, 'unregistered!', [] ]; + const resp = [1, "unregistered!", []]; callback(null, resp); done(); }); const nh = rosnodejs.nh; - const sub = nh.subscribe(topic, msgType, - (data) => {}, - { queueSize: 1, throttleMs: 1000 } - ); + const sub = nh.subscribe(topic, msgType, (data) => {}, { + queueSize: 1, + throttleMs: 1000, + }); - sub.on('registered', () => { + sub.on("registered", () => { nh.unsubscribe(topic); }); }); - it('registerPublisher', (done) => { - const topic = '/test_topic'; - const msgType = 'std_msgs/String'; - masterStub.on('registerPublisher', (err, params, callback) => { + it("registerPublisher", (done) => { + const topic = "/test_topic"; + const msgType = "std_msgs/String"; + primaryStub.on("registerPublisher", (err, params, callback) => { expect(params.length).to.equal(4); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(topic); expect(params[2]).to.equal(msgType); - expect(params[3].startsWith('http://')).to.be.true; + expect(params[3].startsWith("http://")).to.be.true; const info = netUtils.getAddressAndPortFromUri(params[3]); - expect(info.host).to.be.a('string'); + expect(info.host).to.be.a("string"); expect(info.host.length).to.not.equal(0); - expect(info.port).to.be.a('string'); + expect(info.port).to.be.a("string"); expect(info.port.length).to.not.equal(0); - const resp = [ 1, 'registered!', [] ]; + const resp = [1, "registered!", []]; callback(null, resp); done(); }); const nh = rosnodejs.getNodeHandle(); - const pub = nh.advertise(topic, msgType, { latching: true, - queueSize: 1, - throttleMs: 1000 } - ); + const pub = nh.advertise(topic, msgType, { + latching: true, + queueSize: 1, + throttleMs: 1000, + }); }); - it('unregisterPublisher', (done) => { - const topic = '/test_topic'; - const msgType = 'std_msgs/String'; + it("unregisterPublisher", (done) => { + const topic = "/test_topic"; + const msgType = "std_msgs/String"; let nodeUri; - masterStub.on('registerPublisher', (err, params, callback) => { + primaryStub.on("registerPublisher", (err, params, callback) => { nodeUri = params[3]; - const resp = [ 1, 'registered!', [] ]; + const resp = [1, "registered!", []]; callback(null, resp); }); - masterStub.on('unregisterPublisher', (err, params, callback) => { + primaryStub.on("unregisterPublisher", (err, params, callback) => { expect(params.length).to.equal(3); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(topic); expect(params[2]).to.equal(nodeUri); - const resp = [ 1, 'unregistered!', [] ]; + const resp = [1, "unregistered!", []]; callback(null, resp); done(); }); const nh = rosnodejs.nh; - const pub = nh.advertise(topic, msgType, { latching: true, - queueSize: 1, - throttleMs: 1000 } - ); + const pub = nh.advertise(topic, msgType, { + latching: true, + queueSize: 1, + throttleMs: 1000, + }); - pub.on('registered', () => { + pub.on("registered", () => { nh.unadvertise(topic); }); }); - it('registerService', (done) => { - const service = '/test_service'; - const srvType = 'std_srvs/Empty'; - masterStub.on('registerService', (err, params, callback) => { + it("registerService", (done) => { + const service = "/test_service"; + const srvType = "std_srvs/Empty"; + primaryStub.on("registerService", (err, params, callback) => { expect(params.length).to.equal(4); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(service); - expect(params[2].startsWith('rosrpc://')).to.be.true; + expect(params[2].startsWith("rosrpc://")).to.be.true; let info = netUtils.getAddressAndPortFromUri(params[2]); - expect(info.host).to.be.a('string'); + expect(info.host).to.be.a("string"); expect(info.host.length).to.not.equal(0); - expect(info.port).to.be.a('string'); + expect(info.port).to.be.a("string"); expect(info.port.length).to.not.equal(0); - expect(params[3].startsWith('http://')).to.be.true; + expect(params[3].startsWith("http://")).to.be.true; info = netUtils.getAddressAndPortFromUri(params[3]); - expect(info.host).to.be.a('string'); + expect(info.host).to.be.a("string"); expect(info.host.length).to.not.equal(0); - expect(info.port).to.be.a('string'); + expect(info.port).to.be.a("string"); expect(info.port.length).to.not.equal(0); - const resp = [ 1, 'registered!', [] ]; + const resp = [1, "registered!", []]; callback(null, resp); }); const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => {}); - serv.on('registered', done); + serv.on("registered", done); }); - it('unregisterService', (done) => { - const service = '/test_service'; - const srvType = 'std_srvs/Empty'; + it("unregisterService", (done) => { + const service = "/test_service"; + const srvType = "std_srvs/Empty"; let serviceUri = null; - masterStub.on('registerService', (err, params, callback) => { + primaryStub.on("registerService", (err, params, callback) => { serviceUri = params[2]; - const resp = [1, 'registered!', '']; + const resp = [1, "registered!", ""]; callback(null, resp); }); - masterStub.on('unregisterService', (err, params, callback) => { + primaryStub.on("unregisterService", (err, params, callback) => { expect(params.length).to.equal(3); expect(params[0]).to.equal(nodeName); expect(params[1]).to.equal(service); expect(params[2]).to.equal(serviceUri); - const resp = [ 1, 'unregistered!', [] ]; + const resp = [1, "unregistered!", []]; callback(null, resp); done(); }); @@ -277,59 +286,62 @@ describe('Protocol Test', () => { const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => {}); - serv.on('registered', () => { + serv.on("registered", () => { nh.unadvertiseService(service); }); }); }); - describe('Pub-Sub', () => { - const topic = '/test_topic'; - const msgType = 'std_msgs/Int8'; + describe("Pub-Sub", () => { + const topic = "/test_topic"; + const msgType = "std_msgs/Int8"; beforeEach(() => { let pubInfo = null; let subInfo = null; - masterStub.on('getUri', (err, params, callback) => { - const resp = [ 1, '', 'localhost:11311/' ] + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", "localhost:11311/"]; callback(null, resp); }); - masterStub.on('registerSubscriber', (err, params, callback) => { + primaryStub.on("registerSubscriber", (err, params, callback) => { subInfo = params[3]; //console.log('sub reg ' + params); //console.log(pubInfo); - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (pubInfo) { resp[2].push(pubInfo); } callback(null, resp); }); - masterStub.on('unregisterSubscriber', (err, params, callback) => { - const resp = [1, 'You did it!', subInfo ? 1 : 0]; + primaryStub.on("unregisterSubscriber", (err, params, callback) => { + const resp = [1, "You did it!", subInfo ? 1 : 0]; callback(null, resp); subInfo = null; }); - masterStub.on('registerPublisher', (err, params, callback) => { + primaryStub.on("registerPublisher", (err, params, callback) => { //console.log('pub reg'); pubInfo = params[3]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; if (subInfo) { resp[2].push(pubInfo); - let subAddrParts = subInfo.replace('http://', '').split(':'); - let client = xmlrpc.createClient({host: subAddrParts[0], port: subAddrParts[1]}); + let subAddrParts = subInfo.replace("http://", "").split(":"); + let client = xmlrpc.createClient({ + host: subAddrParts[0], + port: subAddrParts[1], + }); let data = [1, topic, [pubInfo]]; - client.methodCall('publisherUpdate', data, (err, response) => { }); + client.methodCall("publisherUpdate", data, (err, response) => {}); } callback(null, resp); }); - masterStub.on('unregisterPublisher', (err, params, callback) => { - const resp = [1, 'You did it!', pubInfo ? 1 : 0]; + primaryStub.on("unregisterPublisher", (err, params, callback) => { + const resp = [1, "You did it!", pubInfo ? 1 : 0]; callback(null, resp); pubInfo = null; }); @@ -345,120 +357,137 @@ describe('Protocol Test', () => { nh._node._spinner.clear(); - // remove any master api handlers we set up - masterStub.removeAllListeners(); + // remove any primary api handlers we set up + primaryStub.removeAllListeners(); }); - it('Basic', (done) => { + it("Basic", (done) => { const nh = rosnodejs.nh; - const valsToSend = [1,2,3]; + const valsToSend = [1, 2, 3]; const valsReceived = new Set(valsToSend); const pub = nh.advertise(topic, msgType, { queueSize: 3 }); - const sub = nh.subscribe(topic, msgType, (data) => { - valsReceived.delete(data.data); - if (valsReceived.size === 0) { - done(); - } - }, {queueSize: 3}); + const sub = nh.subscribe( + topic, + msgType, + (data) => { + valsReceived.delete(data.data); + if (valsReceived.size === 0) { + done(); + } + }, + { queueSize: 3 } + ); - pub.on('connection', () => { + pub.on("connection", () => { valsToSend.forEach((val) => { - pub.publish({data: val}); + pub.publish({ data: val }); }); }); }); - it('Latch', (done) => { + it("Latch", (done) => { const nh = rosnodejs.nh; const pub = nh.advertise(topic, msgType, { latching: true }); - pub.publish({data: 1}); + pub.publish({ data: 1 }); - pub.on('registered', () => { + pub.on("registered", () => { const sub = nh.subscribe(topic, msgType, (data) => { done(); }); }); }); - it('Invalid Without Resolve Causes Error', (done) => { + it("Invalid Without Resolve Causes Error", (done) => { const nh = rosnodejs.nh; - const sub = nh.subscribe(topic, 'std_msgs/String'); + const sub = nh.subscribe(topic, "std_msgs/String"); // NOTE: you'll see an error logged here - THAT'S OK // WE'RE EXPECTING AN ERROR TO LOG const logCapture = { write(rec) { - if (rec.level === rosnodejs.log.levelFromName['error'] && - rec.msg.startsWith('Error when publishing')) - { + if ( + rec.level === rosnodejs.log.levelFromName["error"] && + rec.msg.startsWith("Error when publishing") + ) { done(); } - } + }, }; rosnodejs.log.addStream({ - type: 'raw', - name: 'testCapture', + type: "raw", + name: "testCapture", stream: logCapture, - level: 'error' + level: "error", }); - sub.on('registered', () => { - const pub = nh.advertise(topic, 'std_msgs/String', {latching: true}); + sub.on("registered", () => { + const pub = nh.advertise(topic, "std_msgs/String", { latching: true }); - pub.on('connection', () => { + pub.on("connection", () => { pub.publish({}); }); - pub.on('error', (err) => { + pub.on("error", (err) => { nh._node._spinner._queueLocked = false; }); }); }); - it('Resolve', (done) => { + it("Resolve", (done) => { const nh = rosnodejs.nh; - const sub = nh.subscribe(topic, 'std_msgs/String', (data) => { + const sub = nh.subscribe(topic, "std_msgs/String", (data) => { done(); }); - sub.on('registered', () => { - const pub = nh.advertise(topic, 'std_msgs/String', { latching: true, resolve: true }); + sub.on("registered", () => { + const pub = nh.advertise(topic, "std_msgs/String", { + latching: true, + resolve: true, + }); - pub.on('registered', () => { + pub.on("registered", () => { pub.publish({}); }); }); }); - it('Throttle Pub', function(done) { + it("Throttle Pub", function (done) { this.slow(1000); const nh = rosnodejs.nh; - const valsToSend = [1,2,3,4,5,6,7,8,9,10]; - const pub = nh.advertise(topic, msgType, { queueSize: 1, throttleMs: 100}); + const valsToSend = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10]; + const pub = nh.advertise(topic, msgType, { + queueSize: 1, + throttleMs: 100, + }); let numMsgsReceived = 0; - const sub = nh.subscribe(topic, msgType, (data) => { - ++numMsgsReceived; - if (data.data === valsToSend[valsToSend.length -1]) { - expect(numMsgsReceived).to.equal(valsToSend.length/2 + 1); - done(); - } - }, {queueSize: 1}); + const sub = nh.subscribe( + topic, + msgType, + (data) => { + ++numMsgsReceived; + if (data.data === valsToSend[valsToSend.length - 1]) { + expect(numMsgsReceived).to.equal(valsToSend.length / 2 + 1); + done(); + } + }, + { queueSize: 1 } + ); - pub.on('connection', () => { + pub.on("connection", () => { valsToSend.forEach((val, index) => { setTimeout(() => { - pub.publish({data: val}); - }, 50*index); + pub.publish({ data: val }); + }, 50 * index); }); }); }); - it('Disconnect Pub', (done) => { + it("Disconnect Pub", (done) => { const nh = rosnodejs.nh; const pub = nh.advertise(topic, msgType); const sub = nh.subscribe(topic, msgType, (data) => { @@ -468,16 +497,18 @@ describe('Protocol Test', () => { pub.shutdown(); expect(pub.getNumSubscribers()).to.equal(0); - sub.on('disconnect', () => { + sub.on("disconnect", () => { expect(sub.getNumPublishers()).to.equal(0); - done() + done(); }); }); - pub.on('connection', () => { pub.publish({data: 1}); }); + pub.on("connection", () => { + pub.publish({ data: 1 }); + }); }); - it('Disconnect Sub', (done) => { + it("Disconnect Sub", (done) => { const nh = rosnodejs.nh; const pub = nh.advertise(topic, msgType); const sub = nh.subscribe(topic, msgType, (data) => { @@ -487,22 +518,24 @@ describe('Protocol Test', () => { sub.shutdown(); expect(sub.getNumPublishers()).to.equal(0); - pub.on('disconnect', () => { + pub.on("disconnect", () => { expect(pub.getNumSubscribers()).to.equal(0); - done() + done(); }); }); - pub.on('connection', () => { pub.publish({data: 1}); }); + pub.on("connection", () => { + pub.publish({ data: 1 }); + }); }); - it('Shutdown Subscriber During Registration', function(done) { + it("Shutdown Subscriber During Registration", function (done) { this.slow(1600); const nh = rosnodejs.nh; const sub = nh.subscribe(topic, msgType); - sub.on('registered', () => { - throwNext('Subscriber should never have registered!'); + sub.on("registered", () => { + throwNext("Subscriber should never have registered!"); }); sub.shutdown(); @@ -511,50 +544,51 @@ describe('Protocol Test', () => { setTimeout(done, 500); }); - it('Shutdown Subscriber Requesting Topic', function(done) { + it("Shutdown Subscriber Requesting Topic", function (done) { this.slow(1600); const nh = rosnodejs.nh; const pub = nh.advertise(topic, msgType); - pub.on('registered', () => { + pub.on("registered", () => { const sub = nh.subscribe(topic, msgType); - sub.on('registered', () => { + sub.on("registered", () => { sub.shutdown(); }); - sub.on('connection', () => { - throwNext('Sub should not have gotten connection'); - }) + sub.on("connection", () => { + throwNext("Sub should not have gotten connection"); + }); }); // if we haven't seen thrown by now we should be good setTimeout(done, 500); }); - it('Shutdown Subscriber Connecting to Publisher', function(done) { + it("Shutdown Subscriber Connecting to Publisher", function (done) { this.slow(1600); const nh = rosnodejs.nh; // manually construct a subscriber... - const subImpl = new SubscriberImpl({ + const subImpl = new SubscriberImpl( + { topic, - type: 'std_msgs/String', - typeClass: rosnodejs.require('std_msgs').msg.String + type: "std_msgs/String", + typeClass: rosnodejs.require("std_msgs").msg.String, }, - nh._node); + nh._node + ); const sub = new Subscriber(subImpl); const SOCKET_CONNECT_CACHED = net.Socket.prototype.connect; const SOCKET_END_CACHED = net.Socket.prototype.end; - sub.on('registered', () => { - - net.Socket.prototype.connect = function(port, address, callback) { + sub.on("registered", () => { + net.Socket.prototype.connect = function (port, address, callback) { process.nextTick(() => { callback(); }); }; - net.Socket.prototype.end = function() { + net.Socket.prototype.end = function () { process.nextTick(() => { net.Socket.prototype.connect = SOCKET_CONNECT_CACHED; net.Socket.prototype.end = SOCKET_END_CACHED; @@ -567,18 +601,21 @@ describe('Protocol Test', () => { SOCKET_END_CACHED.call(this); }; - subImpl._handleTopicRequestResponse([1, 'ok', ['TCPROS', 'junk_address', 1234]], 'http://junk_address:1234'); + subImpl._handleTopicRequestResponse( + [1, "ok", ["TCPROS", "junk_address", 1234]], + "http://junk_address:1234" + ); sub.shutdown(); }); }); - it('Shutdown Publisher During Registration', function(done) { + it("Shutdown Publisher During Registration", function (done) { this.slow(1600); const nh = rosnodejs.nh; const pub = nh.advertise(topic, msgType); - pub.on('registered', () => { - throwNext('Publisher should never have registered!'); + pub.on("registered", () => { + throwNext("Publisher should never have registered!"); }); pub.shutdown(); @@ -587,16 +624,16 @@ describe('Protocol Test', () => { setTimeout(done, 500); }); - it('Shutdown Publisher With Queued Message', function(done) { + it("Shutdown Publisher With Queued Message", function (done) { this.slow(1600); const nh = rosnodejs.nh; const sub = nh.subscribe(topic, msgType, () => { - throwNext('Subscriber should never have gotten messages!'); + throwNext("Subscriber should never have gotten messages!"); }); let pub = nh.advertise(topic, msgType); - pub.on('connection', () => { - pub.publish({data: 1}); + pub.on("connection", () => { + pub.publish({ data: 1 }); pub.shutdown(); }); @@ -604,11 +641,11 @@ describe('Protocol Test', () => { setTimeout(done, 500); }); - it('Shutdown Subscriber With Pending Publisher Client', function(done) { + it("Shutdown Subscriber With Pending Publisher Client", function (done) { this.slow(1600); const nh = rosnodejs.nh; const sub = nh.subscribe(topic, msgType, () => { - throwNext('Subscriber should never have gotten messages!'); + throwNext("Subscriber should never have gotten messages!"); }); let pub = nh.advertise(topic, msgType); @@ -616,7 +653,7 @@ describe('Protocol Test', () => { // the subscriber's connection header and sent a response back // the subscriber will not have validated the publisher's connection // header though so it should have a pending publisher entry. - pub.on('connection', () => { + pub.on("connection", () => { const impl = sub._impl; expect(Object.keys(impl._pendingPubClients)).to.have.lengthOf(1); @@ -635,63 +672,61 @@ describe('Protocol Test', () => { }); }); - it('2 Publishers on Same Topic', function(done) { + it("2 Publishers on Same Topic", function (done) { this.slow(2000); const nh = rosnodejs.nh; let msg1; const sub = nh.subscribe(topic, msgType, (msg) => { - msg1 = msg.data; + msg1 = msg.data; }); - const pub1 = nh.advertise(topic, msgType, {latching: true}); - const pub2 = nh.advertise(topic, msgType, {latching: true}); + const pub1 = nh.advertise(topic, msgType, { latching: true }); + const pub2 = nh.advertise(topic, msgType, { latching: true }); expect(pub1).to.not.equal(pub2); - expect(pub1._impl.listenerCount('connection')).to.equal(2); - expect(pub2._impl.listenerCount('connection')).to.equal(2); + expect(pub1._impl.listenerCount("connection")).to.equal(2); + expect(pub2._impl.listenerCount("connection")).to.equal(2); - pub1.publish({data: 1}); + pub1.publish({ data: 1 }); - sub.once('message', ({data}) => { + sub.once("message", ({ data }) => { expect(sub.getNumPublishers()).to.equal(1); expect(data).to.equal(1); - pub2.publish({data: 2}); - sub.once('message', ({data}) => { + pub2.publish({ data: 2 }); + sub.once("message", ({ data }) => { expect(data).to.equal(2); - pub1.shutdown() - .then(() => { + pub1.shutdown().then(() => { expect(pub1._impl).to.equal(null); - expect(pub2._impl.listenerCount('connection')).to.equal(1); + expect(pub2._impl.listenerCount("connection")).to.equal(1); expect(sub.getNumPublishers()).to.equal(1); - pub2.publish({data: 3}); + pub2.publish({ data: 3 }); - sub.once('message', ({data}) => { + sub.once("message", ({ data }) => { expect(data).to.equal(3); - pub2.shutdown() - .then(() => { + pub2.shutdown().then(() => { expect(sub.getNumPublishers()).to.equal(0); expect(pub2._impl).to.equal(null); done(); }); }); - }) + }); }); - }) + }); }); - it('2 Subscribers on Same Topic', function(done) { + it("2 Subscribers on Same Topic", function (done) { this.slow(2000); const nh = rosnodejs.nh; let msg1; const sub1 = nh.subscribe(topic, msgType, (msg) => { - msg1 = msg.data; + msg1 = msg.data; }); let msg2; @@ -700,37 +735,35 @@ describe('Protocol Test', () => { }); expect(sub1).to.not.equal(sub2); - expect(sub1._impl.listenerCount('connection')).to.equal(2); - expect(sub2._impl.listenerCount('connection')).to.equal(2); + expect(sub1._impl.listenerCount("connection")).to.equal(2); + expect(sub2._impl.listenerCount("connection")).to.equal(2); - const pub = nh.advertise(topic, msgType, {latching: true}); + const pub = nh.advertise(topic, msgType, { latching: true }); - pub.publish({data: 1}); + pub.publish({ data: 1 }); - sub2.once('message', () => { + sub2.once("message", () => { expect(pub.getNumSubscribers()).to.equal(1); expect(msg1).to.equal(msg2); - pub.publish({data: 25}); + pub.publish({ data: 25 }); - sub2.once('message', () => { + sub2.once("message", () => { expect(msg1).to.equal(msg2); msg1 = null; msg2 = null; - sub1.shutdown() - .then(() => { + sub1.shutdown().then(() => { expect(sub1._impl).to.equal(null); - expect(sub2._impl.listenerCount('connection')).to.equal(1); - pub.publish({data: 30}); + expect(sub2._impl.listenerCount("connection")).to.equal(1); + pub.publish({ data: 30 }); - sub2.once('message', () => { + sub2.once("message", () => { expect(msg1).to.equal(null); expect(msg2).to.equal(30); expect(pub.getNumSubscribers()).to.equal(1); - sub2.shutdown() - .then(() => { + sub2.shutdown().then(() => { expect(sub2._impl).to.equal(null); expect(pub.getNumSubscribers()).to.equal(0); done(); @@ -742,37 +775,36 @@ describe('Protocol Test', () => { }); }); - describe('Service', () => { - const service = '/test_service'; - const srvType = 'std_srvs/Empty'; + describe("Service", () => { + const service = "/test_service"; + const srvType = "std_srvs/Empty"; beforeEach(() => { let serviceInfo = null; - masterStub.on('getUri', (err, params, callback) => { - const resp = [1, '', 'localhost:11311/']; + primaryStub.on("getUri", (err, params, callback) => { + const resp = [1, "", "localhost:11311/"]; callback(null, resp); }); - masterStub.on('registerService', (err, params, callback) => { + primaryStub.on("registerService", (err, params, callback) => { serviceInfo = params[2]; - const resp = [1, 'You did it!', []]; + const resp = [1, "You did it!", []]; callback(null, resp); }); - masterStub.on('unregisterService', (err, params, callback) => { - const resp = [1, 'You did it!', serviceInfo ? 1 : 0]; + primaryStub.on("unregisterService", (err, params, callback) => { + const resp = [1, "You did it!", serviceInfo ? 1 : 0]; callback(null, resp); serviceInfo = null; }); - masterStub.on('lookupService', (err, params, callback) => { + primaryStub.on("lookupService", (err, params, callback) => { if (serviceInfo) { const resp = [1, "you did it", serviceInfo]; callback(null, resp); - } - else { + } else { const resp = [-1, "no provider", ""]; callback(null, resp); } @@ -789,11 +821,11 @@ describe('Protocol Test', () => { nh._node._spinner.clear(); - // remove any master api handlers we set up - masterStub.removeAllListeners(); + // remove any primary api handlers we set up + primaryStub.removeAllListeners(); }); - it('Call and Response', (done) => { + it("Call and Response", (done) => { const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => { return true; @@ -801,18 +833,18 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - return client.call({}); - }) - .then(() => { - done(); - }) - .catch((err) => { - throwNext(err); - }) + .then(() => { + return client.call({}); + }) + .then(() => { + done(); + }) + .catch((err) => { + throwNext(err); + }); }); - it('Asynchronous Call and Response', (done) => { + it("Asynchronous Call and Response", (done) => { const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => { return Promise.resolve(true); @@ -820,18 +852,18 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - return client.call({}); - }) - .then(() => { - done(); - }) - .catch((err) => { - throwNext(err); - }) + .then(() => { + return client.call({}); + }) + .then(() => { + done(); + }) + .catch((err) => { + throwNext(err); + }); }); - it('Service Failure', (done) => { + it("Service Failure", (done) => { const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => { return false; @@ -839,23 +871,22 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - return client.call({}); - }) - .then(() => { - throwNext('Service call succeeded when it shouldn\'t have'); - }) - .catch((err) => { - if (err.code === 'E_ROSSERVICEFAILED') { - done(); - } - else { - console.error('Service call failed with unexpected error'); - } - }); + .then(() => { + return client.call({}); + }) + .then(() => { + throwNext("Service call succeeded when it shouldn't have"); + }) + .catch((err) => { + if (err.code === "E_ROSSERVICEFAILED") { + done(); + } else { + console.error("Service call failed with unexpected error"); + } + }); }); - it('Service Shutdown While Registering', function (done) { + it("Service Shutdown While Registering", function (done) { this.slow(1600); const nh = rosnodejs.nh; @@ -864,8 +895,8 @@ describe('Protocol Test', () => { }); // hook into registered event - this should not fire - serv.on('registered', () => { - throw new Error('Service should never have registered!'); + serv.on("registered", () => { + throw new Error("Service should never have registered!"); }); // kill the service while the asynchronous registration is happening @@ -875,24 +906,23 @@ describe('Protocol Test', () => { setTimeout(done, 500); }); - it('Service Shutdown During Call', function(done) { + it("Service Shutdown During Call", function (done) { this.slow(1600); const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => { - throw new Error('Service callback should never have been called!'); + throw new Error("Service callback should never have been called!"); }); let connected = false; - serv.on('connection', () => { + serv.on("connection", () => { // we've received the client header but not the request - SHUT IT DOWN connected = true; serv.shutdown(); }); const client = nh.serviceClient(service, srvType); - nh.waitForService(service) - .then(() => { + nh.waitForService(service).then(() => { client.call({}); }); @@ -900,7 +930,7 @@ describe('Protocol Test', () => { setTimeout(done, 500); }); - it('Service Shutdown Handling Call', function(done) { + it("Service Shutdown Handling Call", function (done) { this.slow(1600); const nh = rosnodejs.nh; @@ -912,21 +942,20 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - return client.call({}); - }) - .catch((err) => { - expect(err.message).to.equal('Connection was closed'); - done(); - }); + .then(() => { + return client.call({}); + }) + .catch((err) => { + expect(err.message).to.equal("Connection was closed"); + done(); + }); }); - it('Service Shutdown Handling Asynchronous Call', function(done) { + it("Service Shutdown Handling Asynchronous Call", function (done) { this.slow(1600); const nh = rosnodejs.nh; const serv = nh.advertiseService(service, srvType, (req, resp) => { - return new Promise((resolve) => { setTimeout(() => { serv.shutdown(); @@ -937,17 +966,17 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - return client.call({}); - }) - .catch((err) => { - expect(err.message).to.equal('Connection was closed'); - done(); - }); + .then(() => { + return client.call({}); + }) + .catch((err) => { + expect(err.message).to.equal("Connection was closed"); + done(); + }); }); - it('Service Unregistered During Call', (done) => { - // simulate a service disconnecting between the lookupService call to ROS Master + it("Service Unregistered During Call", (done) => { + // simulate a service disconnecting between the lookupService call to ROS Primary // and the connection to the service node's TCPROS server // cache a reference to net.connect - we'll replace it @@ -960,110 +989,109 @@ describe('Protocol Test', () => { const client = nh.serviceClient(service, srvType); nh.waitForService(service) - .then(() => { - - // we've verified that the service exists - replace the net.connect call (used to initiate the TCPROS - // connection) with a bogus one that throws an error - net.connect = (info) => { - const sock = new net.Socket(); - process.nextTick(() => { - const error = new Error(`connect ECONNREFUSED ${info.host}:${info.port}`); - error.code = 'ECONNREFUSED'; - error.errno = 'ECONNREFUSED'; - error.address = info.host; - error.port = info.port; - - // just to make sure there isn't some other error that comes through - should be unnecessary - error.rosnodejstesting = true; - sock.emit('error', error); - }); - return sock; - }; + .then(() => { + // we've verified that the service exists - replace the net.connect call (used to initiate the TCPROS + // connection) with a bogus one that throws an error + net.connect = (info) => { + const sock = new net.Socket(); + process.nextTick(() => { + const error = new Error( + `connect ECONNREFUSED ${info.host}:${info.port}` + ); + error.code = "ECONNREFUSED"; + error.errno = "ECONNREFUSED"; + error.address = info.host; + error.port = info.port; + + // just to make sure there isn't some other error that comes through - should be unnecessary + error.rosnodejstesting = true; + sock.emit("error", error); + }); + return sock; + }; - return client.call({}); - }) - .catch((err) => { - if (err.code === 'ECONNREFUSED' && err.rosnodejstesting) { - // nice! restore net.connect and close up shop - net.connect = NET_CONNECT_FUNC; - done(); - } - }) + return client.call({}); + }) + .catch((err) => { + if (err.code === "ECONNREFUSED" && err.rosnodejstesting) { + // nice! restore net.connect and close up shop + net.connect = NET_CONNECT_FUNC; + done(); + } + }); }); }); - describe('Shutdown', () => { - let masterStub; + describe("Shutdown", () => { + let primaryStub; before(() => { - stopMasterStub(() => { - masterStub = new MasterStub('localhost', MASTER_PORT); - masterStub.provideAll(); + stopPrimaryStub(() => { + primaryStub = new PrimaryStub("localhost", PRIMARY_PORT); + primaryStub.provideAll(); }); - return rosnodejs.shutdown() - .then(() => { + return rosnodejs.shutdown().then(() => { rosnodejs.reset(); }); }); after((done) => { - masterStub.shutdown() - .then(() => { + primaryStub.shutdown().then(() => { done(); }); - }) + }); - it('Shutdown after successful start with master running', function(done) { - rosnodejs.initNode(nodeName, initArgs) - .then(() => { - return rosnodejs.shutdown(); - }) - .then(() => { - rosnodejs.reset(); - expect(gotEvent).to.be.true; - done(); - }); + it("Shutdown after successful start with primary running", function (done) { + rosnodejs + .initNode(nodeName, initArgs) + .then(() => { + return rosnodejs.shutdown(); + }) + .then(() => { + rosnodejs.reset(); + expect(gotEvent).to.be.true; + done(); + }); let gotEvent = false; - rosnodejs.on('shutdown', () => { + rosnodejs.on("shutdown", () => { gotEvent = true; }); }); - it('Shutdown after successful start with master down', function(done) { - rosnodejs.initNode(nodeName, initArgs) - .then(() => { - return masterStub.shutdown(); - }) - .then(() => { - return rosnodejs.shutdown(); - }) - .then(() => { - rosnodejs.reset(); - expect(gotEvent).to.be.true; - done(); - }); + it("Shutdown after successful start with primary down", function (done) { + rosnodejs + .initNode(nodeName, initArgs) + .then(() => { + return primaryStub.shutdown(); + }) + .then(() => { + return rosnodejs.shutdown(); + }) + .then(() => { + rosnodejs.reset(); + expect(gotEvent).to.be.true; + done(); + }); let gotEvent = false; - rosnodejs.on('shutdown', () => { + rosnodejs.on("shutdown", () => { gotEvent = true; }); }); - it('Shutdown when unable to connect to master', function(done) { - rosnodejs.initNode(nodeName, initArgs) - .then(() => { - throwNext('Node should not have initialized!'); + it("Shutdown when unable to connect to primary", function (done) { + rosnodejs.initNode(nodeName, initArgs).then(() => { + throwNext("Node should not have initialized!"); }); let gotEvent = false; - rosnodejs.on('shutdown', () => { + rosnodejs.on("shutdown", () => { gotEvent = true; }); setTimeout(() => { - rosnodejs.shutdown() - .then(() => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); expect(gotEvent).to.be.true; done(); @@ -1071,22 +1099,18 @@ describe('Protocol Test', () => { }, 500); }); - it('Spinner is cleared out when shutdown', function(done) { - masterStub.listen(); - masterStub.provideAll(); + it("Spinner is cleared out when shutdown", function (done) { + primaryStub.listen(); + primaryStub.provideAll(); let gotEvent = false; - rosnodejs.initNode(nodeName, initArgs) - .then((nh) => { - - const pub = nh.advertise('/chatter', 'std_msgs/String'); - const sub = nh.subscribe('/chatter', 'std_msgs/String'); - pub.publish({data: 'hi'}); - + rosnodejs.initNode(nodeName, initArgs).then((nh) => { + const pub = nh.advertise("/chatter", "std_msgs/String"); + const sub = nh.subscribe("/chatter", "std_msgs/String"); + pub.publish({ data: "hi" }); - rosnodejs.shutdown() - .then(() => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); expect(gotEvent).to.be.true; expect(nh._node._spinner._spinTimer.clientCallQueue).to.be.undefined; @@ -1094,193 +1118,188 @@ describe('Protocol Test', () => { }); }); - rosnodejs.on('shutdown', () => { + rosnodejs.on("shutdown", () => { gotEvent = true; }); }); }); - describe('Parameters', function() { - let masterStub; + describe("Parameters", function () { + let primaryStub; before(() => { - masterStub = new MasterStub('localhost', MASTER_PORT); - masterStub.provideAll(); + primaryStub = new PrimaryStub("localhost", PRIMARY_PORT); + primaryStub.provideAll(); - return rosnodejs.shutdown() - .then(() => { + return rosnodejs.shutdown().then(() => { rosnodejs.reset(); return rosnodejs.initNode(nodeName, initArgs); - }) + }); }); after(() => { - masterStub.shutdown(); - return rosnodejs.shutdown() - .then(() => { + primaryStub.shutdown(); + return rosnodejs.shutdown().then(() => { rosnodejs.reset(); }); }); - it('Set', function(done) { + it("Set", function (done) { const nh = rosnodejs.nh; - nh.setParam('/key', 2) - .then(() => { - expect(masterStub._params['/key']).to.equal(2); + nh.setParam("/key", 2).then(() => { + expect(primaryStub._params["/key"]).to.equal(2); done(); }); }); - it('Get', function(done) { + it("Get", function (done) { const nh = rosnodejs.nh; - nh.getParam('/key') - .then((result) => { + nh.getParam("/key").then((result) => { expect(result).to.equal(2); - expect(masterStub._params['/key']).to.equal(2); + expect(primaryStub._params["/key"]).to.equal(2); done(); }); }); - it('Has', function(done) { + it("Has", function (done) { const nh = rosnodejs.nh; - nh.hasParam('/key') - .then((result) => { + nh.hasParam("/key").then((result) => { expect(result).to.be.true; - expect(masterStub._params['/key']).to.equal(2); + expect(primaryStub._params["/key"]).to.equal(2); done(); }); }); - it('Delete', function(done) { + it("Delete", function (done) { const nh = rosnodejs.nh; - nh.deleteParam('/key') - .then(() => { - expect(masterStub._params['/key']).to.be.undefined; + nh.deleteParam("/key").then(() => { + expect(primaryStub._params["/key"]).to.be.undefined; done(); }); }); - it('Full', function(done) { + it("Full", function (done) { const nh = rosnodejs.nh; - nh.getParam('/missing') - .then(() => throwNext('Get should reject')) - .catch(() => { - return nh.hasParam('/missing') - }) - .catch(() => throwNext('Has should resolve')) - .then((result) => { - expect(result).to.be.false; - return nh.setParam('/exists', 1); - }) - .catch(() => throwNext('Set should resolve')) - .then(() => { - expect(masterStub._params['/exists']).to.equal(1); - return nh.hasParam('/exists'); - }) - .catch(() => throwNext('Has should resolve')) - .then((result) => { - expect(result).to.be.true; - return nh.getParam('/exists'); - }) - .catch(() => throwNext('Get should resolve')) - .then((result) => { - expect(result).to.equal(1); - return nh.deleteParam('/missing'); - }) - .then(() => throwNext('Delete should reject')) - .catch((err) => { - return nh.deleteParam('/exists'); - }) - .catch(() => throwNext('Delete should resolve')) - .then(() => { - return nh.hasParam('/exists'); - }) - .catch(() => throwNext('Has should resolve')) - .then((result) => { - expect(result).to.be.false; - done(); - }); + nh.getParam("/missing") + .then(() => throwNext("Get should reject")) + .catch(() => { + return nh.hasParam("/missing"); + }) + .catch(() => throwNext("Has should resolve")) + .then((result) => { + expect(result).to.be.false; + return nh.setParam("/exists", 1); + }) + .catch(() => throwNext("Set should resolve")) + .then(() => { + expect(primaryStub._params["/exists"]).to.equal(1); + return nh.hasParam("/exists"); + }) + .catch(() => throwNext("Has should resolve")) + .then((result) => { + expect(result).to.be.true; + return nh.getParam("/exists"); + }) + .catch(() => throwNext("Get should resolve")) + .then((result) => { + expect(result).to.equal(1); + return nh.deleteParam("/missing"); + }) + .then(() => throwNext("Delete should reject")) + .catch((err) => { + return nh.deleteParam("/exists"); + }) + .catch(() => throwNext("Delete should resolve")) + .then(() => { + return nh.hasParam("/exists"); + }) + .catch(() => throwNext("Has should resolve")) + .then((result) => { + expect(result).to.be.false; + done(); + }); }); }); - describe('initialization', () => { - const MASTER_PORT = 55599; - const rosMasterUri = `http://localhost:${MASTER_PORT}`; + describe("initialization", () => { + const PRIMARY_PORT = 55599; + const rosPrimaryUri = `http://localhost:${PRIMARY_PORT}`; // don't provide any of the expected APIs so the node won't initialize - const masterStub = new MasterStub('localhost', MASTER_PORT); + const primaryStub = new PrimaryStub("localhost", PRIMARY_PORT); // turn off warnings about methods not existing since we're purposefully // not providing any methods - masterStub.verbose = false; + primaryStub.verbose = false; afterEach((done) => { - rosnodejs.shutdown() - .then(() => { + rosnodejs.shutdown().then(() => { rosnodejs.reset(); done(); }); - }) + }); after((done) => { - masterStub.shutdown() - .then(() => { done() }); - }) + primaryStub.shutdown().then(() => { + done(); + }); + }); - it('wait forever', function(done) { + it("wait forever", function (done) { this.slow(3000); this.timeout(5000); - rosnodejs.initNode('test_node', { rosMasterUri }) - .then(() => { + rosnodejs.initNode("test_node", { rosPrimaryUri }).then(() => { process.nextTick(() => { - throw new Error('Node shouldnt initialize'); + throw new Error("Node shouldnt initialize"); }); }); setTimeout(done, 2000); }); - it('wait a little', function(done) { + it("wait a little", function (done) { this.slow(3000); this.timeout(5000); let timeout; - rosnodejs.initNode('test_node', { rosMasterUri, timeout: 1000 }) - .then(() => { - process.nextTick(() => { - throw new Error('Node shouldnt initialize'); + rosnodejs + .initNode("test_node", { rosPrimaryUri, timeout: 1000 }) + .then(() => { + process.nextTick(() => { + throw new Error("Node shouldnt initialize"); + }); + }) + .catch((err) => { + clearTimeout(timeout); + done(); }); - }) - .catch((err) => { - clearTimeout(timeout); - done(); - }) timeout = setTimeout(() => { - throw new Error('Should have timed out!'); + throw new Error("Should have timed out!"); }, 2000); }); - it('wait once', function(done) { + it("wait once", function (done) { this.slow(500); let timeout; - rosnodejs.initNode('test_node', { rosMasterUri, timeout: 0 }) - .then(() => { - process.nextTick(() => { - throw new Error('Node shouldnt initialize'); + rosnodejs + .initNode("test_node", { rosPrimaryUri, timeout: 0 }) + .then(() => { + process.nextTick(() => { + throw new Error("Node shouldnt initialize"); + }); + }) + .catch((err) => { + clearTimeout(timeout); + done(); }); - }) - .catch((err) => { - clearTimeout(timeout); - done(); - }) timeout = setTimeout(() => { - throw new Error('Should have timed out!'); + throw new Error("Should have timed out!"); }, 500); }); });