diff --git a/.travis.yml b/.travis.yml index 47db2ed7..47f16d3c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -7,8 +7,12 @@ branches: only: - develop +env: + - RCLNODEJS_USE_ROSIDL=true + - RCLNODEJS_USE_ROSIDL=false + script: - 'if [ "$DOCKER_USERNAME" != "" ]; then sudo docker login -u $DOCKER_USERNAME -p $DOCKER_PASSWORD; fi' - sudo docker pull ubuntu:focal - sudo docker build -t rcldocker . - - sudo docker run -v $(pwd):/root/rclnodejs --rm rcldocker bash -i -c 'cd /root/rclnodejs && cppcheck --suppress=syntaxError --enable=all src/*.cpp src/*.hpp && ./scripts/build.sh && npm test' + - sudo docker run -e RCLNODEJS_USE_ROSIDL=${RCLNODEJS_USE_ROSIDL} -v $(pwd):/root/rclnodejs --rm rcldocker bash -i -c 'cd /root/rclnodejs && cppcheck --suppress=syntaxError --enable=all src/*.cpp src/*.hpp && ./scripts/build.sh && npm test' diff --git a/README.md b/README.md index 27707245..63c628ef 100644 --- a/README.md +++ b/README.md @@ -5,9 +5,9 @@ | develop | [![Build Status](https://travis-ci.org/RobotWebTools/rclnodejs.svg?branch=develop)](https://travis-ci.org/RobotWebTools/rclnodejs) | [![macOS Build Status](https://circleci.com/gh/RobotWebTools/rclnodejs/tree/develop.svg?style=shield)](https://circleci.com/gh/RobotWebTools/rclnodejs) | [![Build status](https://ci.appveyor.com/api/projects/status/upbc7tavdag1aa5e/branch/develop?svg=true)](https://ci.appveyor.com/project/minggangw/rclnodejs/branch/develop) | | master | [![Build Status](https://travis-ci.org/RobotWebTools/rclnodejs.svg?branch=master)](https://travis-ci.org/RobotWebTools/rclnodejs) | [![macOS Build Status](https://circleci.com/gh/RobotWebTools/rclnodejs/tree/master.svg?style=shield)](https://circleci.com/gh/RobotWebTools/rclnodejs) | [![Build status](https://ci.appveyor.com/api/projects/status/upbc7tavdag1aa5e/branch/master?svg=true)](https://ci.appveyor.com/project/minggangw/rclnodejs/branch/master) | -**rclnodejs** is a Node.js client library for the Robot Operating System -([ROS 2](https://index.ros.org/doc/ros2/)). It provides a JavaScript API -and tooling for ROS 2 programming. TypeScript declarations, i.e., (*.d.ts), +**rclnodejs** is a Node.js client library for the Robot Operating System +([ROS 2](https://index.ros.org/doc/ros2/)). It provides a JavaScript API +and tooling for ROS 2 programming. TypeScript declarations, i.e., (\*.d.ts), are included to support use in TypeScript projects. Here's an example for how to create a ROS 2 node that publishes a string message in a few lines of JavaScript. @@ -66,6 +66,103 @@ npm i rclnodejs@x.y.z - **Note:** to install rclnodejs from GitHub: add `"rclnodejs":"RobotWebTools/rclnodejs#"` to your `package.json` depdendency section. +## Experimental Message Bindings + +In order to use the new bindings, you must either: + +set RCLNODEJS_USE_ROSIDL=1 environment variable. +or +add a `.npmrc` file in your project directory with `rclnodejs_use_rosidl=true`. + +The new experimental message bindings uses ros interfaces to perform serialization. The main advantage of the new bindings is better performance, it is ~25% faster for large messages (1mb) and ~800% faster for small messages (1kb). It is also safer as memory is managed by v8, you will no longer get undefined behaviors when you try to reference a message outside the subscription callbacks. Also as a result of moving to v8 managed memory, it fixes some memory leaks observed in the current bindings. + +The downside is that the new bindings is not API compatible, it does a number of things differently. + +1. The new bindings initialize nested message as plain js objects instead of the wrappers classes. As a result, they don't contain wrapper methods, for example, this wouldn't work + +```js +const msg = new UInt8MultiArray(); +console.log(msg.hasMember('foo')); // ok, `msg` is a UInt8MultiArrayWrapper +console.log(msg.layout.hasMember('bar')); // error, `layout` is a plain js object, there is no `hasMember` method +``` + +2. There is no array wrappers. + +```js +const UInt8MultiArray = rclnodejs.require('std_msgs').msg.UInt8MultiArray; +const Byte = rclnodejs.require('std_msgs').msg.Byte; +const byteArray = new Byte.ArrayType(10); // error, there is no `ArrayType` +``` + +3. Primitives are initialized to their zero value. + +```js +const Header = rclnodejs.require('std_msgs').msg.Header; +let header = new Header(); +console.log(typeof header.frame_id); // 'string', in the old bindings this would be 'undefined' +``` + +4. Shortform for `std_msg` wrappers are not supported. + +```js +const String = rclnodejs.require('std_msgs').msg.String; +const publisher = node.createPublisher(String, 'topic'); +publisher.publish({ data: 'hello' }); // ok +publisher.publish('hello'); // error, shortform not supported +``` + +5. Primitive arrays are always deserialized to typed arrays. + +```js +const subscription = node.createSubscription( + 'std_msgs/msg/UInt8MultiArray', + 'topic', + (msg) => { + console.log(msg.data instanceof Uint8Array); // always true, even if typed array is disabled in rclnodejs initialization + } +); +``` + +6. No conversion is done until serialization time. + +```js +const UInt8MultiArray = rclnodejs.require('std_msgs').msg.UInt8MultiArray; +const msg = new UInt8MultiArray(); +msg.data = [1, 2, 3]; +console.log(msg.data instanceof Uint8Array); // false, assigning `msg.data` does not automatically convert it to typed array. +``` + +7. Does not throw on wrong types, they are silently converted to their zero value instead. + +```js +const String = rclnodejs.require('std_msgs').msg.String; +const publisher = node.createPublisher(String, 'topic'); +publish.publish({ data: 123 }); // does not throw, data is silently converted to an empty string. +``` + +8. Message memory is managed by v8. There is no longer any need to manually destroy messages and + do other house keeping. + +```js +// With the old bindings, this may result in use-after-free as messages may be deleted when they +// leave the callback, even if there are still references to it. You will have to deep copy the message +// and manually destroy it with its `destroy` method when you don't need it anymore. +// +// This is safe with the new bindings, `lastMessage` will either be `undefined` or the last message received. +// Old messages are automatically garbage collected by v8 as they are no longer reachable. +let lastMessage; +const subscription = node.createSubscription( + 'std_msgs/msg/UInt8MultiArray', + 'topic', + (msg) => { + lastMessage = msg; + } +); +setTimeout(() => { + console.log(lastMessage); +}, 1000); +``` + ## API Documentation API documentation is generated by `jsdoc` and can be viewed in the `docs/` folder or [on-line](http://robotwebtools.org/rclnodejs/docs/index.html). To create a local copy of the documentation run `npm run docs`. @@ -75,6 +172,7 @@ API documentation is generated by `jsdoc` and can be viewed in the `docs/` folde `rclnodejs` API can be used in TypeScript projects. You can find the TypeScript declaration files (\*.d.ts) in the `types/` folder. Your `tsconfig.json` file should include the following compiler options: + ```jsonc { "compilerOptions": { @@ -98,18 +196,19 @@ rclnodejs.init().then(() => { }); ``` -The benefits of using TypeScript become evident when working with more complex use-cases. ROS messages are defined in the `types/interfaces.d.ts` module. This module is updated as part of the `generate-messages` process described in the next section. +The benefits of using TypeScript become evident when working with more complex use-cases. ROS messages are defined in the `types/interfaces.d.ts` module. This module is updated as part of the `generate-messages` process described in the next section. ## ROS2 Interface Message Generation (important) -ROS components communicate by sending and receiving messages described -by the interface definition language (IDL). ROS client libraries such as -rclnodejs are responsible for converting these IDL message descriptions -into source code of their target language. For this, rclnodejs provides -the `generate-messages` npm script that reads in the IDL -messages files of a ROS environment and generates corresponding JavaScript -message interface files. Additionally, the tool generates the TypeScript -`interface.d.ts` file containing declarations for every IDL message file -processed. + +ROS components communicate by sending and receiving messages described +by the interface definition language (IDL). ROS client libraries such as +rclnodejs are responsible for converting these IDL message descriptions +into source code of their target language. For this, rclnodejs provides +the `generate-messages` npm script that reads in the IDL +messages files of a ROS environment and generates corresponding JavaScript +message interface files. Additionally, the tool generates the TypeScript +`interface.d.ts` file containing declarations for every IDL message file +processed. Learn more about ROS interfaces and IDL [here](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/). @@ -122,13 +221,15 @@ stringMsgObject.data = 'hello world'; ``` ### Maintaining Generated JavaScript Message Files -Message files are generated as a post-install step of the rclnodejs -installation process. Thereafter, you will need to manually run the -message generation script when new ROS message packages are installed -for which your ROS2-nodejs project has a dependency. + +Message files are generated as a post-install step of the rclnodejs +installation process. Thereafter, you will need to manually run the +message generation script when new ROS message packages are installed +for which your ROS2-nodejs project has a dependency. ### Running `generate-messages` Utility -To use `generate-messages` from your Nodejs package, create an npm + +To use `generate-messages` from your Nodejs package, create an npm script entry in your package.json file as shown: ``` @@ -136,15 +237,16 @@ script entry in your package.json file as shown: "generate-messages": "generate-messages" // your other scripts here } -```` +``` To run the script use `npm` as follows: + ``` npm run generate-messages ``` -The newly generated JavaScript files can be found at -`/node_modules/rclnodejs/generated/`. +The newly generated JavaScript files can be found at +`/node_modules/rclnodejs/generated/`. ## Contributing diff --git a/benchmark/rclnodejs/message/c-struct-to-js-obj.js b/benchmark/rclnodejs/message/c-struct-to-js-obj.js new file mode 100644 index 00000000..3c82b8ec --- /dev/null +++ b/benchmark/rclnodejs/message/c-struct-to-js-obj.js @@ -0,0 +1,72 @@ +'use strict'; + +/** + * Benchmarks the performance in converting from native C struct to javascript objects. + * Requires the ros package "test_msgs" to be available. + */ +const app = require('commander'); +const generatorOptions = require('../../../generated/generator-options'); + +app.option('-r, --runs ', 'Number of times to run').parse(process.argv); +const runs = app.runs || 1; + +const BasicTypes = require('../../../generated/test_msgs/test_msgs__msg__BasicTypes'); + +if (generatorOptions.idlProvider === 'rosidl') { + const rosMessage = BasicTypes.toRosMessage({ + bool_value: false, + byte_value: 0, + char_value: 0, + float32_value: 0, + float64_value: 0, + int8_value: 0, + uint8_value: 0, + int16_value: 0, + uint16_value: 0, + int32_value: 0, + uint32_value: 0, + int64_value: BigInt(0), + uint64_value: BigInt(0), + }); + const startTime = process.hrtime(); + for (let i = 0; i < runs; i++) { + BasicTypes.toJsObject(rosMessage); + } + const timeTaken = process.hrtime(startTime); + console.log( + `Benchmark took ${timeTaken[0]} seconds and ${Math.ceil( + timeTaken[1] / 1000000 + )} milliseconds.` + ); +} else { + const msg = new BasicTypes({ + bool_value: false, + byte_value: 0, + char_value: 0, + float32_value: 0, + float64_value: 0, + int8_value: 0, + uint8_value: 0, + int16_value: 0, + uint16_value: 0, + int32_value: 0, + uint32_value: 0, + int64_value: 0, + uint64_value: 0, + }); + msg.freeze(); + const rawMessage = msg._refObject; + const deserializeFunc = process.env.RCLNODEJS_NO_ZEROCOPY + ? (rawMessage) => msg.toPlainObject(msg.deserialize(rawMessage)) + : (rawMessage) => msg.deserialize(rawMessage); + const startTime = process.hrtime(); + for (let i = 0; i < runs; i++) { + deserializeFunc(rawMessage); + } + const timeTaken = process.hrtime(startTime); + console.log( + `Benchmark took ${timeTaken[0]} seconds and ${Math.ceil( + timeTaken[1] / 1000000 + )} milliseconds.` + ); +} diff --git a/benchmark/rclnodejs/message/js-obj-to-c-struct.js b/benchmark/rclnodejs/message/js-obj-to-c-struct.js new file mode 100644 index 00000000..f7c77398 --- /dev/null +++ b/benchmark/rclnodejs/message/js-obj-to-c-struct.js @@ -0,0 +1,68 @@ +'use strict'; + +/** + * Benchmarks the performance in converting from to javascript objects to native C structs. + * Requires the ros package "test_msgs" to be available. + */ +const app = require('commander'); +const generatorOptions = require('../../../generated/generator-options'); + +app.option('-r, --runs ', 'Number of times to run').parse(process.argv); +const runs = app.runs || 1; + +const BasicTypes = require('../../../generated/test_msgs/test_msgs__msg__BasicTypes'); + +if (generatorOptions.idlProvider === 'rosidl') { + const jsObj = { + bool_value: false, + byte_value: 0, + char_value: 0, + float32_value: 0, + float64_value: 0, + int8_value: 0, + uint8_value: 0, + int16_value: 0, + uint16_value: 0, + int32_value: 0, + uint32_value: 0, + int64_value: BigInt(0), + uint64_value: BigInt(0), + }; + const startTime = process.hrtime(); + for (let i = 0; i < runs; i++) { + BasicTypes.toRosMessage(jsObj); + } + const timeTaken = process.hrtime(startTime); + console.log( + `Benchmark took ${timeTaken[0]} seconds and ${Math.ceil( + timeTaken[1] / 1000000 + )} milliseconds.` + ); +} else { + const jsObj = { + bool_value: false, + byte_value: 0, + char_value: 0, + float32_value: 0, + float64_value: 0, + int8_value: 0, + uint8_value: 0, + int16_value: 0, + uint16_value: 0, + int32_value: 0, + uint32_value: 0, + int64_value: 0, + uint64_value: 0, + }; + const startTime = process.hrtime(); + for (let i = 0; i < runs; i++) { + const msg = new BasicTypes(jsObj); + msg.serialize(); + } + const timeTaken = process.hrtime(startTime); + console.log( + `Benchmark took ${timeTaken[0]} seconds and ${Math.ceil( + timeTaken[1] / 1000000 + )} milliseconds.` + ); +} diff --git a/binding.gyp b/binding.gyp index 54f69ec7..70324ece 100644 --- a/binding.gyp +++ b/binding.gyp @@ -10,6 +10,82 @@ 'variables': { 'ros_version': ' { + this.messageInfoIndex[this._messageInfoHash(messageInfo)] = messageInfo; + }); + } + } + + setSpec(messageInfo, spec) { + this.specIndex[this._messageInfoHash(messageInfo)] = spec; + } + + getMessageInfoFromType(type) { + return this.messageInfoIndex[`${type.pkgName}/${type.type}`]; + } + + /** + * Gets a list of all messages that a message depends on. + * @param {string} messageInfo Base message. + * @returns {object[]} An array of message infos. + */ + async getDependentMessages(messageInfo) { + const key = this._messageInfoHash(messageInfo); + let dependentMessages = this.dependentMessagesIndex[key]; + if (dependentMessages === undefined) { + this.dependentMessagesIndex[key] = new Promise(async (res) => { + const set = new Set(); + const spec = await this.getMessageSpec(messageInfo); + spec.fields.forEach((field) => { + if ( + field.type.pkgName && + field.type.pkgName !== messageInfo.pkgName + ) { + // `this.getMessageInfoFromType` must always return the + // same object for the same type for this to work + set.add(this.getMessageInfoFromType(field.type)); + } + }); + res(Array.from(set.values())); + }); + return this.dependentMessagesIndex[key]; + } + return dependentMessages; + } + + /** + * Gets a list of packages that a given package depends on. + * @param {string} pkgName Name of the base package + * @returns {Promise} An array containing name of all dependent packages. + */ + async getDependentPackages(pkgName) { + let dependentPackages = this.dependentPackagesIndex[pkgName]; + if (dependentPackages === undefined) { + this.dependentPackagesIndex[pkgName] = new Promise(async (res) => { + const set = new Set(); + const pkgInfo = this.pkgIndex.get(pkgName); + for (let messageInfo of pkgInfo.messages) { + const spec = await this.getMessageSpec(messageInfo); + spec.fields.forEach((field) => { + if (field.type.pkgName && field.type.pkgName !== pkgName) { + set.add(field.type.pkgName); + } + }); + } + res(Array.from(set.values())); + }); + return this.dependentPackagesIndex[pkgName]; + } + return dependentPackages; + } + + _messageInfoHash(messageInfo) { + return `${messageInfo.pkgName}/${messageInfo.interfaceName}`; + } + + async getMessageSpec(messageInfo) { + let spec = this.specIndex[this._messageInfoHash(messageInfo)]; + if (spec) { + return spec; + } + const promise = new Promise(async (res) => { + const spec = await parser.parseMessageFile( + messageInfo.pkgName, + messageInfo.filePath + ); + this.specIndex[this._messageInfoHash(messageInfo)] = spec; + res(spec); + }); + this.specIndex[this._messageInfoHash(messageInfo)] = promise; + return promise; + } + + async getLinkLibraries(pkgName) { + let linkLibraries = this.linkLibrariesIndex[pkgName]; + if (linkLibraries === undefined) { + this.linkLibrariesIndex[pkgName] = new Promise(async (res) => { + const set = new Set(); + const dependentPackages = await this.getDependentPackages(pkgName); + const dependentLibraries = ( + await Promise.all( + dependentPackages.map((name) => this.getLinkLibraries(name)) + ) + ).flat(); + dependentLibraries.forEach((lib) => set.add(lib)); + + const pkg = this.pkgIndex.get(pkgName); + const generatorCLibs = await this._guessGeneratorCLibs(pkg); + generatorCLibs.forEach((lib) => set.add(lib)); + + res(Array.from(set.values())); + }); + linkLibraries = this.linkLibrariesIndex[pkgName]; + } + return linkLibraries; + } + + /** + * Tries to guess the libraries needed to be linked against for generator_c. + * + * Normally, the typesupport libraries are built at compiled time of the message packages. The + * libraries that have to be linked against are based on the name of the cmake target. Because + * + * 1. We are a third party library, so our typesupport cannot be built at the compile time. + * 2. We are use node-gyp as the build tool, so we can't use cmake to find the link libraries. + * + * The stopgap solution is then to use regexp on the cmake config files to try to find the + * required link libraries. + * + * @param {string} pkg package info + * @param {string} amentRoot ament root directory + * @returns {Promise} an array of generator_c libraries found + */ + async _guessGeneratorCLibs(pkg) { + const cmakeExport = await fs.readFile( + path.join( + pkg.amentRoot, + 'share', + pkg.pkgName, + 'cmake', + 'ament_cmake_export_libraries-extras.cmake' + ), + 'utf-8' + ); + const match = cmakeExport.match( + /set\s*\(\s*(?:_exported_typesupport_libraries|_exported_libraries)\s*"(.*)"/ + ); + if (!match || match.length < 2) { + throw new Error(`unable to find generator_c library for ${pkg}`); + } + const libraries = match[1].replace(/:/g, ';'); + const generatorCLibs = []; + libraries.split(';').forEach((lib) => { + if (lib.endsWith('rosidl_generator_c')) { + generatorCLibs.push(lib); + } + }); + return generatorCLibs; + } +} + dot.templateSettings.strip = false; dot.log = process.env.RCLNODEJS_LOG_VERBOSE || false; const dots = dot.process({ path: path.join(__dirname, '../rosidl_gen/templates'), }); +function pascalToSnakeCase(s) { + let result = s.replace(/(.)([A-Z][a-z]+)/g, '$1_$2'); + result = result.replace(/([a-z0-9])([A-Z])/g, '$1_$2'); + return result.toLowerCase(); +} + +function getRosHeaderField(messageInfo) { + if (isInternalMessage(messageInfo)) { + const interfaceName = messageInfo.interfaceName.slice( + 0, + messageInfo.interfaceName.indexOf('_') + ); + return `${messageInfo.pkgName}/${messageInfo.subFolder}/${pascalToSnakeCase( + interfaceName + )}.h`; + } + return `${messageInfo.pkgName}/${messageInfo.subFolder}/${pascalToSnakeCase( + messageInfo.interfaceName + )}.h`; +} + function removeEmptyLines(str) { return str.replace(/^\s*\n/gm, ''); } @@ -50,15 +239,17 @@ function generateServiceJSStruct(serviceInfo, dir) { return writeGeneratedCode(dir, fileName, generatedCode); } -async function generateMessageJSStruct(messageInfo, dir) { - const spec = await parser.parseMessageFile( - messageInfo.pkgName, - messageInfo.filePath - ); - await generateMessageJSStructFromSpec(messageInfo, dir, spec); +async function generateMessageJSStruct(messageInfo, dir, rosIdlDb, options) { + const spec = await rosIdlDb.getMessageSpec(messageInfo); + await generateMessageJSStructFromSpec(messageInfo, dir, spec, options); } -function generateMessageJSStructFromSpec(messageInfo, dir, spec) { +async function generateMessageJSStructFromSpec( + messageInfo, + dir, + spec, + options +) { dir = path.join(dir, `${spec.baseType.pkgName}`); const fileName = spec.baseType.pkgName + @@ -68,17 +259,236 @@ function generateMessageJSStructFromSpec(messageInfo, dir, spec) { spec.msgName + '.js'; - const generatedCode = removeEmptyLines( - dots.message({ - messageInfo: messageInfo, - spec: spec, - json: JSON.stringify(spec, null, ' '), + let generatedCode; + if (options.idlProvider === 'rosidl') { + generatedCode = removeEmptyLines( + dots.messageRosidl({ + messageInfo: messageInfo, + spec: spec, + json: JSON.stringify(spec, null, ' '), + options, + }) + ); + } else { + generatedCode = removeEmptyLines( + dots.message({ + messageInfo: messageInfo, + spec: spec, + json: JSON.stringify(spec, null, ' '), + options, + }) + ); + } + return writeGeneratedCode(dir, fileName, generatedCode); +} + +function getCppOutputDir(pkgName) { + return path.join('src', 'generated', pkgName); +} + +function getJsType(rosType) { + if (rosType.isArray) { + return 'object'; + } + if (rosType.type === 'int64' || rosType.type === 'uint64') { + return 'bigint'; + } else if ( + rosType.type.startsWith('int') || + rosType.type.startsWith('uint') || + rosType.type.startsWith('float') || + rosType.type === 'double' || + rosType.type === 'byte' || + rosType.type === 'char' + ) { + return 'number'; + } else if (rosType.type === 'string') { + return 'string'; + } else if (rosType.type === 'bool') { + return 'boolean'; + } + return 'object'; +} + +function isInternalField(field) { + return field.name.startsWith('_'); +} + +function isInternalMessage(messageInfo) { + return messageInfo.interfaceName.indexOf('_') !== -1; +} + +// All messages are combined in one cpp file to improve compile time. +async function generateCppDefinitions(pkgName, pkgInfo, rosIdlDb, options) { + if (options.idlProvider !== 'rosidl') { + return; + } + + const getStructType = (messageInfo) => { + return `${messageInfo.pkgName}__${messageInfo.subFolder}__${messageInfo.interfaceName}`; + }; + + const getStructTypeFromRosType = (type) => { + const messageInfo = rosIdlDb.getMessageInfoFromType(type); + return getStructType(messageInfo); + }; + + const messages = await Promise.all([ + ...pkgInfo.messages.map(async (messageInfo) => ({ + info: messageInfo, + spec: await rosIdlDb.getMessageSpec(messageInfo), + structType: getStructType(messageInfo), + })), + ...( + await Promise.all( + pkgInfo.actions.map(async (actionInfo) => { + const msgInfosAndSpecs = await getActionMessageInfosAndSpecs( + actionInfo + ); + return Object.values(msgInfosAndSpecs).map( + async ({ info, spec }) => ({ + info: info, + spec: spec, + structType: getStructType(info), + }) + ); + }) + ) + ).flat(), + ]); + + const includeHeadersSet = new Set(); + messages.forEach(({ info }) => { + includeHeadersSet.add(getRosHeaderField(info)); + }); + const includeHeaders = Array.from(includeHeadersSet.values()); + + const dependentPackages = await rosIdlDb.getDependentPackages(pkgName); + + const source = removeEmptyLines( + dots.cppDefinitions({ + pkgName, + pkgInfo, + messages, + includeHeaders, + dependentPackages, + rosIdlDb, + getStructType, + getStructTypeFromRosType, + getJsType, + isInternalField, }) ); - return writeGeneratedCode(dir, fileName, generatedCode); + + const header = removeEmptyLines( + dots.cppDefinitionsHeader({ + pkgName, + pkgInfo, + messages, + dependentPackages, + rosIdlDb, + getStructType, + getStructTypeFromRosType, + getJsType, + isInternalField, + }) + ); + + const outputDir = getCppOutputDir(pkgName); + await fs.mkdir(outputDir, { recursive: true }); + await fs.writeFile(path.join(outputDir, 'definitions.cpp'), source); + await fs.writeFile(path.join(outputDir, 'definitions.hpp'), header); +} + +async function getActionMessageInfosAndSpecs(actionInfo) { + const spec = await parser.parseActionFile( + actionInfo.pkgName, + actionInfo.filePath + ); + + return { + goal: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_Goal`, + }, + spec: spec.goal, + }, + result: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_Result`, + }, + spec: spec.result, + }, + feedback: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_Feedback`, + }, + spec: spec.feedback, + }, + sendGoalRequest: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_SendGoal_Request`, + }, + spec: actionMsgs.createSendGoalRequestSpec( + actionInfo.pkgName, + actionInfo.interfaceName + ), + }, + sendGoalResponse: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_SendGoal_Response`, + }, + spec: actionMsgs.createSendGoalResponseSpec( + actionInfo.pkgName, + actionInfo.interfaceName + ), + }, + getResultRequest: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_GetResult_Request`, + }, + spec: actionMsgs.createGetResultRequestSpec( + actionInfo.pkgName, + actionInfo.interfaceName + ), + }, + getResultResponse: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_GetResult_Response`, + }, + spec: actionMsgs.createGetResultResponseSpec( + actionInfo.pkgName, + actionInfo.interfaceName + ), + }, + feedbackMessage: { + info: { + pkgName: actionInfo.pkgName, + subFolder: actionInfo.subFolder, + interfaceName: `${actionInfo.interfaceName}_FeedbackMessage`, + }, + spec: actionMsgs.createFeedbackMessageSpec( + actionInfo.pkgName, + actionInfo.interfaceName + ), + }, + }; } -async function generateActionJSStruct(actionInfo, dir) { +async function generateActionJSStruct(actionInfo, dir, options) { const spec = await parser.parseActionFile( actionInfo.pkgName, actionInfo.filePath @@ -91,7 +501,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_Goal`, }, dir, - spec.goal + spec.goal, + options ); const resultMsg = generateMessageJSStructFromSpec( @@ -101,7 +512,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_Result`, }, dir, - spec.result + spec.result, + options ); const feedbackMsg = generateMessageJSStructFromSpec( @@ -111,7 +523,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_Feedback`, }, dir, - spec.feedback + spec.feedback, + options ); const sendGoalRequestSpec = actionMsgs.createSendGoalRequestSpec( @@ -125,7 +538,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_SendGoal_Request`, }, dir, - sendGoalRequestSpec + sendGoalRequestSpec, + options ); const sendGoalResponseSpec = actionMsgs.createSendGoalResponseSpec( @@ -139,7 +553,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_SendGoal_Response`, }, dir, - sendGoalResponseSpec + sendGoalResponseSpec, + options ); const sendGoalSrv = generateServiceJSStruct( @@ -162,7 +577,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_GetResult_Request`, }, dir, - getResultRequestSpec + getResultRequestSpec, + options ); const getResultResponseSpec = actionMsgs.createGetResultResponseSpec( @@ -176,7 +592,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_GetResult_Response`, }, dir, - getResultResponseSpec + getResultResponseSpec, + options ); const getResultSrv = generateServiceJSStruct( @@ -199,7 +616,8 @@ async function generateActionJSStruct(actionInfo, dir) { interfaceName: `${actionInfo.interfaceName}_FeedbackMessage`, }, dir, - feedbackMessageSpec + feedbackMessageSpec, + options ); const fileName = @@ -230,16 +648,44 @@ async function generateActionJSStruct(actionInfo, dir) { ]); } -async function generateJSStructFromIDL(pkg, dir) { +async function generateJSStructFromIDL(pkg, dir, rosIdlDb, options) { await Promise.all([ ...pkg.messages.map((messageInfo) => - generateMessageJSStruct(messageInfo, dir) + generateMessageJSStruct(messageInfo, dir, rosIdlDb, options) ), ...pkg.services.map((serviceInfo) => generateServiceJSStruct(serviceInfo, dir) ), - ...pkg.actions.map((actionInfo) => generateActionJSStruct(actionInfo, dir)), + ...pkg.actions.map((actionInfo) => + generateActionJSStruct(actionInfo, dir, options) + ), ]); } -module.exports = generateJSStructFromIDL; +async function generateTypesupportGypi(pkgsEntries, rosIdlDb, options) { + await fs.mkdir(path.join('src', 'generated'), { recursive: true }); + if (options.idlProvider !== 'rosidl') { + await fs.writeFile( + path.join('src', 'generated', 'typesupport.gypi'), + '# not using rosidl\n{}' + ); + return; + } + + const pkgs = await Promise.all( + pkgsEntries.map(async ([pkgName, pkgInfo]) => ({ + pkgName, + pkgInfo, + dependencies: await rosIdlDb.getDependentPackages(pkgName), + })) + ); + const rendered = removeEmptyLines(dots.typesupportGyp({ pkgs })); + await fs.writeFile(path.join('src', 'generated', 'binding.gyp'), rendered); +} + +module.exports = { + RosIdlDb, + generateJSStructFromIDL, + generateCppDefinitions, + generateTypesupportGypi, +}; diff --git a/rosidl_gen/index.js b/rosidl_gen/index.js index bab0b6cb..e5e4ea07 100644 --- a/rosidl_gen/index.js +++ b/rosidl_gen/index.js @@ -14,22 +14,65 @@ 'use strict'; +const child_process = require('child_process'); +const fsp = require('fs').promises; const fse = require('fs-extra'); -const generateJSStructFromIDL = require('./idl_generator.js'); +const { + RosIdlDb, + generateJSStructFromIDL, + generateCppDefinitions, + generateTypesupportGypi: generateTypesupportGyp, +} = require('./idl_generator.js'); +const os = require('os'); const packages = require('./packages.js'); const path = require('path'); +const { useRosIdl } = require('../options'); const generatedRoot = path.join(__dirname, '../generated/'); const installedPackagePaths = process.env.AMENT_PREFIX_PATH.split( path.delimiter ); -async function generateInPath(path) { - const pkgs = await packages.findPackagesInDirectory(path); +async function generateInPaths(paths, options) { + const pkgsInPaths = await Promise.all( + paths.map((path) => packages.findPackagesInDirectory(path)) + ); + const pkgs = new Map(); + pkgsInPaths.forEach((m, i) => { + for (let [pkgName, pkgInfo] of m.entries()) { + pkgs.set(pkgName, { ...pkgInfo, amentRoot: paths[i] }); + } + }); + // skip this package as it contains message that is invalid + pkgs.delete('libstatistics_collector'); + + const rosIdlDb = new RosIdlDb(pkgs); + const pkgsInfo = Array.from(pkgs.values()); + const pkgsEntries = Array.from(pkgs.entries()); + await Promise.all( - pkgsInfo.map((pkgInfo) => generateJSStructFromIDL(pkgInfo, generatedRoot)) + pkgsInfo.map((pkgInfo) => + generateJSStructFromIDL(pkgInfo, generatedRoot, rosIdlDb, options) + ) ); + + if (options.idlProvider === 'rosidl') { + await Promise.all( + pkgsEntries.map(([pkgName, pkgInfo]) => { + generateCppDefinitions(pkgName, pkgInfo, rosIdlDb, options); + }) + ); + await generateTypesupportGyp(pkgsEntries, rosIdlDb, options); + await child_process.spawn('npx', ['--no-install', 'node-gyp', 'rebuild'], { + cwd: `${__dirname}/../src/generated`, + stdio: 'inherit', + env: { + ...process.env, + JOBS: os.cpus().length, + }, + }); + } } async function generateAll(forcedGenerating) { @@ -42,8 +85,13 @@ async function generateAll(forcedGenerating) { path.join(__dirname, 'generator.json'), path.join(generatedRoot, 'generator.json') ); - await Promise.all( - installedPackagePaths.map((path) => generateInPath(path)) + const options = { + idlProvider: useRosIdl ? 'rosidl' : 'ref', + }; + await generateInPaths(installedPackagePaths, options); + await fsp.writeFile( + path.join(generatedRoot, 'generator-options.js'), + `module.exports = ${JSON.stringify(options)}` ); } } @@ -55,7 +103,7 @@ const generator = { }, generateAll, - generateInPath, + generateInPaths, generatedRoot, }; diff --git a/rosidl_gen/templates/cppDefinitions.dot b/rosidl_gen/templates/cppDefinitions.dot new file mode 100644 index 00000000..46524c63 --- /dev/null +++ b/rosidl_gen/templates/cppDefinitions.dot @@ -0,0 +1,167 @@ +// This file is automatically generated by rclnodejs +// +// *** DO NOT EDIT directly +// + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-variable" +#pragma GCC diagnostic ignored "-Wunused-but-set-variable" + +#include "definitions.hpp" +#include "../../type_conversion.hpp" + +{{~ it.includeHeaders : header}} +#include <{{=header}}> +{{~}} + +namespace rclnodejs { + +{{~ it.messages : message}} +NAN_MODULE_INIT(rclnodejs__{{=message.structType}}::Init) { + auto clazz = Nan::New(); + clazz->SetClassName(Nan::New("{{=message.info.interfaceName}}").ToLocalChecked()); + clazz->Set(Nan::New("createRosMessage").ToLocalChecked(), Nan::New(rclnodejs__{{=message.structType}}::CreateRosMessage)); + clazz->Set(Nan::New("writeRosMessage").ToLocalChecked(), Nan::New(rclnodejs__{{=message.structType}}::WriteRosMessage)); + clazz->Set(Nan::New("toJsObject").ToLocalChecked(), Nan::New(rclnodejs__{{=message.structType}}::ToJsObject)); + clazz->Set(Nan::New("initSequence").ToLocalChecked(), Nan::New(rclnodejs__{{=message.structType}}::InitSequence)); + Nan::Set(target, Nan::New("{{=message.info.interfaceName}}").ToLocalChecked(), Nan::GetFunction(clazz).ToLocalChecked()); +} + +NAN_METHOD(rclnodejs__{{=message.structType}}::CreateRosMessage) { + auto* data = {{=message.structType}}__create(); + auto buffer = Nan::NewBuffer(reinterpret_cast(data), sizeof(*data), [](auto* data, auto) { + {{=message.structType}}__destroy(reinterpret_cast<{{=message.structType}}*>(data)); + }, nullptr).ToLocalChecked(); + info.GetReturnValue().Set(buffer); +} + +NAN_METHOD(rclnodejs__{{=message.structType}}::WriteRosMessage) { + auto typesupport = Nan::To(info[0]).ToLocalChecked(); + auto js_obj = Nan::To(info[1]).ToLocalChecked(); + {{=message.structType}}* msg; + if (info[2]->IsExternal()) { + msg = reinterpret_cast<{{=message.structType}}*>(info[2].As()->Value()); + } else { + auto* data = node::Buffer::Data(info[2]); + auto offset = info[2].As()->ByteOffset(); + msg = reinterpret_cast<{{=message.structType}}*>(data + offset); + } + +{{~ message.spec.fields : field}} +{{? !it.isInternalField(field)}} + [&](){ + auto js_value = Nan::Get(js_obj, Nan::New("{{=field.name}}").ToLocalChecked()).ToLocalChecked(); + if (js_value->IsNullOrUndefined()) { + // default value is initialized when message is created. + return; + } +{{ +const jsType = it.getJsType(field.type); +}} +{{? !field.type.isArray}} +{{? field.type.isPrimitiveType}} + msg->{{=field.name}} = ToNativeChecked{{=field.name}})>(js_value); +{{??}} + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + auto typesupport_func = Nan::To(Nan::Get(typesupport_msg, Nan::New("_writeRosMessage").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + v8::Local argv[] = { + js_value, + Nan::New(&msg->{{=field.name}}) + }; + Nan::Call(typesupport_func, Nan::New(), 2, argv).ToLocalChecked(); +{{?}} +{{??}} +{{? field.type.isFixedSizeArray}} +{{? field.type.isPrimitiveType}} + WriteNativeArray{{=field.name}})>>(js_value, msg->{{=field.name}}, {{=field.type.arraySize}}); +{{??}} + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + WriteNativeObjectArray{{=field.name}})>>(js_value, msg->{{=field.name}}, {{=field.type.arraySize}}, typesupport_msg); +{{?}} +{{??}} +{{? field.type.arraySize === null}} + size_t capacity = 0xffffffffffffffff; +{{??}} + size_t capacity = {{=field.type.arraySize}}; +{{?}} +{{? field.type.isPrimitiveType}} + WriteNativeSequence{{=field.name}})>(js_value, &msg->{{=field.name}}, capacity); +{{??}} + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + WriteNativeObjectSequence{{=field.name}})>>(js_value, &msg->{{=field.name}}, capacity, typesupport_msg); +{{?}} +{{?}} +{{?}} + }(); +{{?}} +{{~}} +} + +NAN_METHOD(rclnodejs__{{=message.structType}}::ToJsObject) { + auto typesupport = Nan::To(info[0]).ToLocalChecked(); + auto buffer = info[1].As()->Buffer(); + auto* data = reinterpret_cast(buffer->GetContents().Data()); + auto offset = info[1].As()->ByteOffset(); + auto* msg = reinterpret_cast<{{=message.structType}}*>(data + offset); + + auto js_obj = Nan::New(); +{{~ message.spec.fields : field}} +{{? !it.isInternalField(field)}} + { +{{? !field.type.isArray}} +{{? field.type.isPrimitiveType}} + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), ToJsChecked(msg->{{=field.name}})); +{{??}} + auto child_buffer = v8::Uint8Array::New(buffer, reinterpret_cast(&msg->{{=field.name}}) - data, sizeof(msg->{{=field.name}})); + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + auto typesupport_func = Nan::To(Nan::Get(typesupport_msg, Nan::New("_toJsObject").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + v8::Local argv[] = { + std::move(child_buffer) + }; + auto {{=field.name}}_js_obj = Nan::Call(typesupport_func, Nan::New(), 1, argv).ToLocalChecked(); + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), {{=field.name}}_js_obj); +{{?}} +{{??}} +{{? field.type.isFixedSizeArray}} + size_t field_offset = reinterpret_cast(msg->{{=field.name}}) - data; +{{? field.type.isPrimitiveType}} + auto js_array = ToJsArrayChecked{{=field.name}})>>(buffer, field_offset, {{=field.type.arraySize}}); + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), std::move(js_array)); +{{??}} + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), ToJsObjectArrayChecked{{=field.name}})>>(buffer, field_offset, {{=field.type.arraySize}}, typesupport_msg)); +{{?}} +{{??}} + auto sequence_buffer = Nan::NewBuffer(reinterpret_cast(msg->{{=field.name}}.data), msg->{{=field.name}}.size * sizeof(decltype(*msg->{{=field.name}}.data)), [](char*, void*) {}, nullptr).ToLocalChecked().As(); + Nan::Set(sequence_buffer->Buffer(), Nan::New("_rclnodejs_owner").ToLocalChecked(), info[1]).ToChecked(); +{{? field.type.isPrimitiveType}} + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), ToJsArrayChecked{{=field.name}}.data)>>(sequence_buffer->Buffer(), 0, msg->{{=field.name}}.size)); +{{??}} + auto typesupport_msg = Nan::To(Nan::Get(typesupport, Nan::New("{{=field.type.pkgName}}/{{=field.type.type}}").ToLocalChecked()).ToLocalChecked()).ToLocalChecked(); + Nan::Set(js_obj, Nan::New("{{=field.name}}").ToLocalChecked(), ToJsObjectArrayChecked{{=field.name}}.data)>>(sequence_buffer->Buffer(), 0, msg->{{=field.name}}.size, typesupport_msg)); +{{?}} +{{?}} +{{?}} + } +{{?}} +{{~}} + info.GetReturnValue().Set(js_obj); +} + +NAN_METHOD(rclnodejs__{{=message.structType}}::InitSequence) { + auto size = Nan::To(info[0]).ToChecked(); + auto* msg = reinterpret_cast<{{=message.structType}}__Sequence*>(info[1].As()->Value()); + {{=message.structType}}__Sequence__init(msg, size); +} + +{{~}} + +NAN_MODULE_WORKER_ENABLED({{=it.pkgName}}, [](auto target) { +{{~ it.messages : message}} + rclnodejs__{{=message.structType}}::Init(target); +{{~}} +}); + +} // namespace rclnodejs + +#pragma GCC diagnostic pop diff --git a/rosidl_gen/templates/cppDefinitionsHeader.dot b/rosidl_gen/templates/cppDefinitionsHeader.dot new file mode 100644 index 00000000..5ce06a65 --- /dev/null +++ b/rosidl_gen/templates/cppDefinitionsHeader.dot @@ -0,0 +1,31 @@ +// This file is automatically generated by rclnodejs +// +// *** DO NOT EDIT directly +// + +#ifndef RCLNODEJS_{{=it.pkgName.toUpperCase()}}_DEFINITIONS_HPP_ +#define RCLNODEJS_{{=it.pkgName.toUpperCase()}}_DEFINITIONS_HPP_ + +#include + +namespace rclnodejs { + +{{~ it.messages : message }} +class rclnodejs__{{=message.structType}} { + public: + static NAN_MODULE_INIT(Init); + + private: + static NAN_METHOD(CreateRosMessage); + + static NAN_METHOD(WriteRosMessage); + + static NAN_METHOD(ToJsObject); + + static NAN_METHOD(InitSequence); +}; +{{~}} + +} // namespace rclnodejs + +#endif diff --git a/rosidl_gen/templates/messageRosidl.dot b/rosidl_gen/templates/messageRosidl.dot new file mode 100644 index 00000000..53975e8d --- /dev/null +++ b/rosidl_gen/templates/messageRosidl.dot @@ -0,0 +1,271 @@ +// This file is automatically generated by Intel rclnodejs +// +// *** DO NOT EDIT directly +// + +'use strict'; + +{{ +let objectWrapper = it.spec.msgName + 'Wrapper'; + +const compactMsgDefJSON = JSON.stringify(JSON.parse(it.json)); + +if (it.spec.fields.length === 0) { + it.spec.isEmpty = true; + /* Following rosidl_generator_c style, put a bool member named '_dummy' */ + it.spec.fields.push({ + "type": { + "isArray": false, + "pkgName": null, + "type": "bool", + "isDynamicArray": false, + "stringUpperBound": null, + "isUpperBound": false, + "isPrimitiveType": true, + "isFixedSizeArray": false, + "arraySize": null + }, + "name": "_dummy" + }); +} /* if */ + +function getPrimitiveNameByType(type) { + if (type.type === 'bool') { + return 'Bool'; + } else if (type.type === 'int8') { + return 'Int8'; + } else if (type.type === 'uint8') { + return 'UInt8'; + } else if (type.type === 'int16') { + return 'Int16'; + } else if (type.type === 'uint16') { + return 'UInt16'; + } else if (type.type === 'int32') { + return 'Int32'; + } else if (type.type === 'uint32') { + return 'UInt32'; + } else if (type.type === 'int64') { + return 'Int64'; + } else if (type.type === 'uint64') { + return 'UInt64'; + } else if (type.type === 'float64') { + return 'Float64'; + } else if (type.type === 'float32') { + return 'Float32'; + } else if (type.type === 'char') { + return 'Char'; + } else if (type.type === 'byte') { + return 'Byte'; + } else if (type.type === 'string' || type.type === 'wstring') { + return 'String'; + } else { + return ''; + } +} + +const primitiveBaseType = ['Bool', 'Int8', 'UInt8', 'Int16', 'UInt16', 'Int32', 'UInt32', + 'Int64', 'UInt64', 'Float64', 'Float32', 'Char', 'Byte', 'String']; + +let existedModules = []; + +function isExisted(requiredModule) { + return existedModules.indexOf(requiredModule) !== -1; +} + +function isPrimitivePackage(baseType) { + return primitiveBaseType.indexOf(baseType.type) !== -1; +} + +function shouldRequire(baseType, fieldType) { + let requiredModule = '{{=getPackageNameByType(fieldType)}}/{{=getModulePathByType(fieldType)}}'; + let shouldRequire = !fieldType.isPrimitiveType; + + if (shouldRequire && !isExisted(requiredModule)) { + existedModules.push(requiredModule); + return true; + } else { + return false; + } +} + +function getWrapperNameByType(type) { + if (type.isPrimitiveType) { + return getPrimitiveNameByType(type) + 'Wrapper'; + } else { + return type.type + 'Wrapper'; + } +} + +function getModulePathByType(type, messageInfo) { + if (type.isPrimitiveType) { + return 'std_msgs__msg__' + getPrimitiveNameByType(type) + '.js'; + } + + if ( + messageInfo && + messageInfo.subFolder === 'action' && + messageInfo.pkgName === type.pkgName && + (type.type.endsWith('_Goal') || type.type.endsWith('_Result') || type.type.endsWith('_Feedback')) + ) { + return type.pkgName + '__action__' + type.type + '.js'; + } + + return type.pkgName + '__msg__' + type.type + '.js'; +} + +function getPackageNameByType(type) { + if (type.isPrimitiveType) { + return 'std_msgs'; + } else { + return type.pkgName; + } +} + +function extractMemberNames(fields) { + let memberNames = []; + fields.forEach(field => { + memberNames.push(field.name); + }); + return JSON.stringify(memberNames); +} +}} + +const deepcopy = require('deepcopy'); +const typesupport = require('../../src/generated/build/Release/{{=it.messageInfo.pkgName}}__rosidl_node').{{=it.messageInfo.interfaceName}}; + +const typesupportDeps = {}; +{{~ it.spec.fields :field}} + {{? shouldRequire(it.spec.baseType, field.type)}} +const {{=getWrapperNameByType(field.type)}} = require('../../generated/{{=getPackageNameByType(field.type)}}/{{=getModulePathByType(field.type, it.messageInfo)}}'); + {{? it.options.idlProvider === 'rosidl' && field.type.pkgName}} +typesupportDeps['{{=field.type.pkgName}}/{{=field.type.type}}'] = {{=getWrapperNameByType(field.type)}}; + {{?}} + {{?}} +{{~}} + +// Define the wrapper class. +class {{=objectWrapper}} { + constructor(other) { + this._rawRos = undefined; + if (other === undefined) { + this._rawRos = {{=objectWrapper}}._createRosMessage(); + this._proxyObj = {{=objectWrapper}}._toJsObject(this._rawRos); + } else if (other instanceof {{=objectWrapper}}) { + this._proxyObj = deepcopy(other._proxyObj); + } else { + this._proxyObj = other; + } + } + + static _createRosMessage() { + return typesupport.createRosMessage(); + } + + static _toJsObject(rawRos) { + return typesupport.toJsObject(typesupportDeps, rawRos); + } + + static _toRosMessage(obj) { + const rosMessage = {{=objectWrapper}}._createRosMessage(); + {{=objectWrapper}}._writeRosMessage(obj, rosMessage); + return rosMessage; + } + + static _writeRosMessage(obj, rawRos) { + typesupport.writeRosMessage(typesupportDeps, obj, rawRos); + } + + static _initSequence(size, rawRos) { + typesupport.initSequence(size, rawRos); + } + + toRawROS() { + this.freeze(); + return this._rawRos; + } + + freeze(own = false, checkConsistency = false) { + this._rawRos = {{=objectWrapper}}._toRosMessage(this._proxyObj); + } + + serialize() { + return this.toRawROS(); + } + + deserialize(rawRos) { + this._proxyObj = {{=objectWrapper}}._toJsObject(rawRos); + } + + toPlainObject(enableTypedArray) { + return this._proxyObj; + } + + static freeStruct(refObject) { + // managed by v8 gc + } + + static destoryRawROS(msg) { + // managed by v8 gc + } + + static type() { + return {pkgName: '{{=it.messageInfo.pkgName}}', subFolder: '{{=it.messageInfo.subFolder}}', interfaceName: '{{=it.messageInfo.interfaceName}}'}; + } + + static isPrimitive() { + return {{=isPrimitivePackage(it.spec.baseType)}}; + } + + static get isROSArray() { + return false; + } + + get refObject() { + return this._rawRos; + } + + {{~ it.spec.fields :field}} + get {{=field.name}}() { + return this._proxyObj['{{=field.name}}']; + } + + set {{=field.name}}(value) { + this._proxyObj['{{=field.name}}'] = value; + } + {{~}} + + copy(other) { + this._proxyObj = deepcopy(other._proxyObj); + } + + static get classType() { + return {{=objectWrapper}}; + } + + static get ROSMessageDef() { + return {{=compactMsgDefJSON}}; + } + + hasMember(name) { + let memberNames = {{=extractMemberNames(it.spec.fields)}}; + return memberNames.indexOf(name) !== -1; + } +} + +{{? it.spec.constants != undefined && it.spec.constants.length}} +// Define constants ({{=it.spec.constants.length}} in total) +{{~ it.spec.constants :c}} +{{? c.type === "string"}} +Object.defineProperty({{=objectWrapper}}, "{{=c.name}}", {value: "{{=c.value}}", writable: false, enumerable: true, configurable: true}); +{{?? true}} +Object.defineProperty({{=objectWrapper}}, "{{=c.name}}", {value: {{=c.value}}, writable: false, enumerable: true, configurable: true}); +{{?}} +{{~}} +{{?}} + +module.exports = {{=objectWrapper}}; + +/* + * The following is the original spec object coming from parser: +{{=it.json}} +*/ diff --git a/rosidl_gen/templates/typesupportGyp.dot b/rosidl_gen/templates/typesupportGyp.dot new file mode 100644 index 00000000..22635177 --- /dev/null +++ b/rosidl_gen/templates/typesupportGyp.dot @@ -0,0 +1,101 @@ +{ + 'target_defaults': { + 'default_configuration': 'Release', + 'configurations': { + 'Debug': { + 'defines': ['DEBUG_ON'], + }, + } + }, + 'target_defaults': { + 'include_dirs': [ + " +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace rclnodejs { + +std::u16string string_to_u16string(const std::string& input) { + std::wstring_convert, char16_t> converter; + return converter.from_bytes(input); +} + +std::string u16string_to_string(const std::u16string& input) { + std::wstring_convert, char16_t> converter; + return converter.to_bytes(input); +} + +template +inline T ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline int8_t ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline uint8_t ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline int16_t ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline uint16_t ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline int64_t ToNativeChecked(v8::Local val) { + return val->IntegerValue(Nan::GetCurrentContext()).ToChecked(); +} + +template <> +inline uint64_t ToNativeChecked(v8::Local val) { + return static_cast( + val->IntegerValue(Nan::GetCurrentContext()).ToChecked()); +} + +template <> +inline float ToNativeChecked(v8::Local val) { + return Nan::To(std::move(val)).ToChecked(); +} + +template <> +inline rosidl_runtime_c__String ToNativeChecked( + v8::Local val) { + rosidl_runtime_c__String ros_string; + rosidl_runtime_c__String__init(&ros_string); + if (!val->IsString()) { + return ros_string; + } + Nan::Utf8String utf8(val); + if (*utf8 == nullptr) { + throw std::runtime_error("failed to convert value to string"); + } + rosidl_runtime_c__String__assign(&ros_string, *utf8); + return ros_string; +} + +template <> +inline rosidl_runtime_c__U16String ToNativeChecked( + v8::Local val) { + rosidl_runtime_c__U16String ros_string; + rosidl_runtime_c__U16String__init(&ros_string); + if (!val->IsString()) { + return ros_string; + } + Nan::Utf8String utf8(val); + if (*utf8 == nullptr) { + throw std::runtime_error("failed to convert value to string"); + } + auto u16s = string_to_u16string(*utf8); + rosidl_runtime_c__U16String__assign( + &ros_string, reinterpret_cast(u16s.c_str())); + return ros_string; +} + +template +inline void _WriteNativeArrayImpl(v8::Local val, NativeT* arr, + size_t len) { + if (!val->IsTypedArray()) { + if (!val->IsArray()) { + return; + } + auto array = val.As(); + if (array->Length() < len) { + len = array->Length(); + } + for (uint32_t i = 0; i < len; ++i) { + auto native = + ToNativeChecked(Nan::Get(array, i).ToLocalChecked()); + arr[i] = native; + } + } else { + auto typed_array = val.As(); + size_t copy_len = typed_array->ByteLength() < len * sizeof(NativeT) + ? typed_array->ByteLength() + : len * sizeof(NativeT); + typed_array->CopyContents(arr, copy_len); + } +} + +template +inline void WriteNativeArray(v8::Local val, T* arr, size_t len) { + if (!val->IsArray()) { + return; + } + auto array = val.As(); + if (array->Length() < len) { + len = array->Length(); + } + for (size_t i = 0; i < len; ++i) { + auto item = Nan::Get(array, i).ToLocalChecked(); + arr[i] = ToNativeChecked(std::move(item)); + } +} + +template <> +inline void WriteNativeArray(v8::Local val, int8_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, uint8_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, int16_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, uint16_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, int32_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, uint32_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, int64_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, uint64_t* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, float* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template <> +inline void WriteNativeArray(v8::Local val, double* arr, + size_t len) { + _WriteNativeArrayImpl(val, arr, len); +} + +template +inline void WriteNativeObjectArray( + const v8::Local& val, T* arr, size_t len, + const v8::Local& typesupport_msg) { + if (!val->IsArray()) { + return; + } + auto array = val.As(); + if (array->Length() < len) { + len = array->Length(); + } + v8::Local argv[2]; + auto typesupport_func = + Nan::To( + Nan::Get(typesupport_msg, + Nan::New("_writeRosMessage").ToLocalChecked()) + .ToLocalChecked()) + .ToLocalChecked(); + for (size_t i = 0; i < len; ++i) { + auto item = Nan::Get(array, i).ToLocalChecked(); + argv[0] = item; + argv[1] = Nan::New(&arr[i]); + Nan::Call(typesupport_func, Nan::New(), 2, argv) + .ToLocalChecked(); + } +} + +template +inline void InitSequence(SequenceT* seq, size_t size); + +template <> +inline void InitSequence( + rosidl_runtime_c__bool__Sequence* seq, size_t size) { + rosidl_runtime_c__bool__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__byte__Sequence* seq, size_t size) { + rosidl_runtime_c__byte__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__char__Sequence* seq, size_t size) { + rosidl_runtime_c__char__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__float__Sequence* seq, size_t size) { + rosidl_runtime_c__float__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__double__Sequence* seq, size_t size) { + rosidl_runtime_c__double__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__int8__Sequence* seq, size_t size) { + rosidl_runtime_c__int8__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__uint8__Sequence* seq, size_t size) { + rosidl_runtime_c__uint8__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__int16__Sequence* seq, size_t size) { + rosidl_runtime_c__int16__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__uint16__Sequence* seq, size_t size) { + rosidl_runtime_c__uint16__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__int32__Sequence* seq, size_t size) { + rosidl_runtime_c__int32__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__uint32__Sequence* seq, size_t size) { + rosidl_runtime_c__uint32__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__int64__Sequence* seq, size_t size) { + rosidl_runtime_c__int64__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__uint64__Sequence* seq, size_t size) { + rosidl_runtime_c__uint64__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__String__Sequence* seq, size_t size) { + rosidl_runtime_c__String__Sequence__init(seq, size); +} + +template <> +inline void InitSequence( + rosidl_runtime_c__U16String__Sequence* seq, size_t size) { + rosidl_runtime_c__U16String__Sequence__init(seq, size); +} + +template +inline void WriteNativeSequence(v8::Local val, SequenceT* seq, + size_t capacity) { + if (!val->IsTypedArray() && !val->IsArray()) { + return; + } + uint32_t len; + if (val->IsTypedArray()) { + len = val.As()->Length(); + } else { + len = val.As()->Length(); + } + if (capacity < len) { + len = capacity; + } + InitSequence(seq, len); + WriteNativeArray(val, seq->data, len); +} + +template +inline void WriteNativeObjectSequence( + const v8::Local& val, SequenceT* seq, size_t capacity, + const v8::Local& typesupport_msg) { + if (!val->IsArray()) { + return; + } + auto array = val.As(); + + auto len = array->Length(); + if (capacity < len) { + len = capacity; + } + + auto typesupport_func = + Nan::To( + Nan::Get(typesupport_msg, Nan::New("_initSequence").ToLocalChecked()) + .ToLocalChecked()) + .ToLocalChecked(); + v8::Local argv[] = {Nan::New(len), Nan::New(seq)}; + Nan::Call(typesupport_func, Nan::New(), 2, argv).ToLocalChecked(); + + WriteNativeObjectArray(val, seq->data, len, typesupport_msg); +} + +template +inline v8::Local ToJsChecked(T val) { + return Nan::New(val); +} + +template <> +inline v8::Local ToJsChecked(int64_t val) { + // max/min safe integer + if (val > 9007199254740991 || val < -9007199254740991) { + return v8::BigInt::New(Nan::GetCurrentContext()->GetIsolate(), val); + } + return Nan::New(val); +} + +template <> +inline v8::Local ToJsChecked(uint64_t val) { + // max/min safe integer + if (val > 9007199254740991) { + return v8::BigInt::NewFromUnsigned(Nan::GetCurrentContext()->GetIsolate(), + val); + } + return Nan::New(val); +} + +template <> +inline v8::Local ToJsChecked( + rosidl_runtime_c__String val) { + return Nan::New(val.data).ToLocalChecked(); +} + +template <> +inline v8::Local ToJsChecked( + rosidl_runtime_c__U16String val) { + return Nan::New(u16string_to_string(reinterpret_cast(val.data))) + .ToLocalChecked(); +} + +inline uint32_t JsArrayMaxLength() { + return std::numeric_limits::max(); +} + +template +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + auto js_array = Nan::New(); + auto* data = reinterpret_cast(buffer->GetContents().Data()); + auto* arr = reinterpret_cast(data + offset); + uint32_t js_len = len > JsArrayMaxLength() ? JsArrayMaxLength() : len; + for (uint32_t i = 0; i < js_len; i++) { + Nan::Set(js_array, i, ToJsChecked(arr[i])); + } + return js_array; +} + +template +inline v8::Local _ToJsTypedArray( + const v8::Local& buffer, size_t offset, size_t len) { + return TypedArrayT::New(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template <> +inline v8::Local ToJsArrayChecked( + const v8::Local& buffer, size_t offset, size_t len) { + return _ToJsTypedArray(buffer, offset, len); +} + +template +inline v8::Local ToJsObjectArrayChecked( + const v8::Local& buffer, size_t offset, size_t len, + const v8::Local& typesupport_msg) { + auto js_array = Nan::New(); + uint32_t js_len = len > JsArrayMaxLength() ? JsArrayMaxLength() : len; + auto typesupport_func = + Nan::To( + Nan::Get(typesupport_msg, Nan::New("_toJsObject").ToLocalChecked()) + .ToLocalChecked()) + .ToLocalChecked(); + v8::Local argv[1]; + for (uint32_t i = 0; i < js_len; ++i) { + argv[0] = v8::Uint8Array::New(buffer, offset + i * sizeof(T), sizeof(T)); + auto js_obj = Nan::Call(typesupport_func, Nan::New(), 1, argv) + .ToLocalChecked(); + Nan::Set(js_array, i, js_obj); + } + return js_array; +} + +} // namespace rclnodejs + +#endif diff --git a/test/client_setup.js b/test/client_setup.js index 5319efd8..8618bd43 100644 --- a/test/client_setup.js +++ b/test/client_setup.js @@ -30,7 +30,7 @@ rclnodejs var publisher = node.createPublisher(Int8, 'back_add_two_ints'); client.waitForService().then(() => { client.sendRequest(request, (response) => { - publisher.publish(response.sum); + publisher.publish({ data: response.sum }); }); }); diff --git a/test/publisher_setup.js b/test/publisher_setup.js index b8939245..0ed92460 100644 --- a/test/publisher_setup.js +++ b/test/publisher_setup.js @@ -26,7 +26,7 @@ rclnodejs var publisher = node.createPublisher(RclString, 'topic'); var timer = node.createTimer(100, () => { - publisher.publish(msg); + publisher.publish({ data: msg }); }); rclnodejs.spin(node); diff --git a/test/test-array-data.js b/test/test-array-data.js index 85d56812..60ba48e6 100644 --- a/test/test-array-data.js +++ b/test/test-array-data.js @@ -20,6 +20,7 @@ const deepEqual = require('deep-equal'); const rclnodejs = require('../index.js'); const translator = require('../rosidl_gen/message_translator.js'); const arrayGen = require('./array_generator.js'); +const { useRosIdl } = require('../options.js'); function isTypedArray(v) { return ArrayBuffer.isView(v) && !(v instanceof DataView); @@ -48,160 +49,179 @@ describe('rclnodejs message communication', function () { data_offset: 0, }; - [ - { - pkg: 'std_msgs', - type: 'Int8MultiArray', - values: [ - { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array - { layout: layout, data: Int8Array.from([-10, 1, 2, 3, 8, 6, 0, -25]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'Int16MultiArray', - values: [ - { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array - { layout: layout, data: Int16Array.from([-10, 1, 2, 3, 8, 6, 0, -25]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'Int32MultiArray', - values: [ - { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array - { layout: layout, data: Int32Array.from([-10, 1, 2, 3, 8, 6, 0, -25]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'Int64MultiArray', - values: [ - { - layout: layout, - data: [-111, 1, 2, 3, 8, 6, 0, -25, Number.MAX_SAFE_INTEGER], - }, // Provide data via Array - ], - }, - { - pkg: 'std_msgs', - type: 'ByteMultiArray', - values: [ - { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array - { layout: layout, data: Uint8Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'UInt8MultiArray', - values: [ - { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array - { layout: layout, data: Uint8Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'UInt16MultiArray', - values: [ - { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array - { layout: layout, data: Uint16Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'UInt32MultiArray', - values: [ - { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array - { layout: layout, data: Uint32Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'UInt64MultiArray', - values: [ - { - layout: layout, - data: [0, 1, 2, 3, 8, 6, 0, 255, Number.MAX_SAFE_INTEGER], - }, // Provide data via Array - ], - }, - { - pkg: 'std_msgs', - type: 'Float32MultiArray', - values: [ - { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array - { - layout: layout, - data: Float32Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), - }, // Provide data via TypedArray - ], - }, - { - pkg: 'std_msgs', - type: 'Float64MultiArray', - values: [ - { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array - { - layout: layout, - data: Float64Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), - }, // Provide data via TypedArray - ], - }, - /* eslint-enable camelcase */ - /* eslint-enable key-spacing */ - /* eslint-enable comma-spacing */ - ].forEach((testData) => { - const topic = testData.topic || 'topic' + testData.type; - testData.values.forEach((v, i) => { - it('Test ' + testData.type + '.copy()' + ', case ' + i, function () { - const MessageType = rclnodejs.require( - testData.pkg + '/msg/' + testData.type - ); - const msg1 = translator.toROSMessage(MessageType, v); - const msg2 = new MessageType(); - msg2.copy(msg1); + // The new bindings initialize nested message as plain js objects instead of the wrappers. + // As a result, they don't contain .hasMember methods that this test needs. + if (!useRosIdl) { + [ + { + pkg: 'std_msgs', + type: 'Int8MultiArray', + values: [ + { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array + { + layout: layout, + data: Int8Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'Int16MultiArray', + values: [ + { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array + { + layout: layout, + data: Int16Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'Int32MultiArray', + values: [ + { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array + { + layout: layout, + data: Int32Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'Int64MultiArray', + values: [ + { + layout: layout, + data: [-111, 1, 2, 3, 8, 6, 0, -25, Number.MAX_SAFE_INTEGER], + }, // Provide data via Array + ], + }, + { + pkg: 'std_msgs', + type: 'ByteMultiArray', + values: [ + { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array + { layout: layout, data: Uint8Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'UInt8MultiArray', + values: [ + { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array + { layout: layout, data: Uint8Array.from([0, 1, 2, 3, 8, 6, 0, 255]) }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'UInt16MultiArray', + values: [ + { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array + { + layout: layout, + data: Uint16Array.from([0, 1, 2, 3, 8, 6, 0, 255]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'UInt32MultiArray', + values: [ + { layout: layout, data: [0, 1, 2, 3, 8, 6, 0, 255] }, // Provide data via Array + { + layout: layout, + data: Uint32Array.from([0, 1, 2, 3, 8, 6, 0, 255]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'UInt64MultiArray', + values: [ + { + layout: layout, + data: [0, 1, 2, 3, 8, 6, 0, 255, Number.MAX_SAFE_INTEGER], + }, // Provide data via Array + ], + }, + { + pkg: 'std_msgs', + type: 'Float32MultiArray', + values: [ + { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array + { + layout: layout, + data: Float32Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), + }, // Provide data via TypedArray + ], + }, + { + pkg: 'std_msgs', + type: 'Float64MultiArray', + values: [ + { layout: layout, data: [-10, 1, 2, 3, 8, 6, 0, -25] }, // Provide data via Array + { + layout: layout, + data: Float64Array.from([-10, 1, 2, 3, 8, 6, 0, -25]), + }, // Provide data via TypedArray + ], + }, + /* eslint-enable camelcase */ + /* eslint-enable key-spacing */ + /* eslint-enable comma-spacing */ + ].forEach((testData) => { + const topic = testData.topic || 'topic' + testData.type; + testData.values.forEach((v, i) => { + it('Test ' + testData.type + '.copy()' + ', case ' + i, function () { + const MessageType = rclnodejs.require( + testData.pkg + '/msg/' + testData.type + ); + const msg1 = translator.toROSMessage(MessageType, v); + const msg2 = new MessageType(); + msg2.copy(msg1); - function checkMessage(msg) { - assert(typeof msg.layout === 'object'); + function checkMessage(msg) { + assert(typeof msg.layout === 'object'); - assert(Array.isArray(msg.layout.dim.data)); - // First element - assert(typeof msg.layout.dim.data[0] === 'object'); - assert(msg.layout.dim.data[0].label === v.layout.dim[0].label); - assert(msg.layout.dim.data[0].size === v.layout.dim[0].size); - assert(msg.layout.dim.data[0].stride === v.layout.dim[0].stride); + assert(Array.isArray(msg.layout.dim.data)); + // First element + assert(typeof msg.layout.dim.data[0] === 'object'); + assert(msg.layout.dim.data[0].label === v.layout.dim[0].label); + assert(msg.layout.dim.data[0].size === v.layout.dim[0].size); + assert(msg.layout.dim.data[0].stride === v.layout.dim[0].stride); - // Second element - assert(typeof msg.layout.dim.data[1] === 'object'); - assert(msg.layout.dim.data[1].label === v.layout.dim[1].label); - assert(msg.layout.dim.data[1].size === v.layout.dim[1].size); - assert(msg.layout.dim.data[1].stride === v.layout.dim[1].stride); + // Second element + assert(typeof msg.layout.dim.data[1] === 'object'); + assert(msg.layout.dim.data[1].label === v.layout.dim[1].label); + assert(msg.layout.dim.data[1].size === v.layout.dim[1].size); + assert(msg.layout.dim.data[1].stride === v.layout.dim[1].stride); - assert(msg.layout.data_offset === v.layout.data_offset); + assert(msg.layout.data_offset === v.layout.data_offset); - assert(msg.data); - if (isTypedArray(v.data)) { - assert.deepStrictEqual(msg.data, v.data); - } else { - assert.ok(deepEqual(msg.data, v.data)); + assert(msg.data); + if (isTypedArray(v.data)) { + assert.deepStrictEqual(msg.data, v.data); + } else { + assert.ok(deepEqual(msg.data, v.data)); + } } - } - checkMessage(msg1); - checkMessage(msg2); + checkMessage(msg1); + checkMessage(msg2); - const o = v.data[0]; - assert(msg1.data[0] == o); - assert(msg2.data[0] == o); + const o = v.data[0]; + assert(msg1.data[0] == o); + assert(msg2.data[0] == o); - const r = Math.round(Math.random() * 100); - msg1.data[0] = r; + const r = Math.round(Math.random() * 100); + msg1.data[0] = r; - assert(msg1.data[0] == r); - assert(msg2.data[0] == o); + assert(msg1.data[0] == r); + assert(msg2.data[0] == o); + }); }); }); - }); + } const uint8Data = arrayGen.generateValues( Array, @@ -225,391 +245,396 @@ describe('rclnodejs message communication', function () { arrayGen.noRound ); - [ - /* eslint-disable camelcase */ - /* eslint-disable key-spacing */ - /* eslint-disable comma-spacing */ - { - pkg: 'sensor_msgs', - type: 'PointCloud2', - arrayType: Uint8Array, - property: 'data', - values: [ - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - height: 240, - width: 320, - fields: [], - is_bigendian: false, - point_step: 16, - row_step: 320 * 16, - data: uint8Data, - is_dense: false, - }, - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - height: 240, - width: 320, - fields: [], - is_bigendian: false, - point_step: 16, - row_step: 320 * 16, - data: Uint8Array.from(uint8Data), - is_dense: false, - }, - ], - }, - { - pkg: 'sensor_msgs', - type: 'Image', - arrayType: Uint8Array, - property: 'data', - values: [ - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - height: 240, - width: 320, - encoding: 'rgba', - is_bigendian: false, - step: 320 * 16, - is_dense: false, - data: uint8Data, - }, - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - height: 240, - width: 320, - encoding: 'rgba', - is_bigendian: false, - step: 320 * 16, - is_dense: false, - data: Uint8Array.from(uint8Data), - }, - ], - }, - { - pkg: 'sensor_msgs', - type: 'CompressedImage', - arrayType: Uint8Array, - property: 'data', - values: [ - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - format: 'jpeg', - data: uint8Data, - }, - { - header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, - format: 'jpeg', - data: Uint8Array.from(uint8Data), - }, - ], - }, - { - pkg: 'sensor_msgs', - type: 'ChannelFloat32', - arrayType: Float32Array, - property: 'values', - values: [ - { name: 'intensity', values: float32Data }, - { name: 'intensity', values: Float32Array.from(float32Data) }, - { - name: 'intensity', - values: Float32Array.from(Float32Array.from(float32Data)), - }, - ], - }, - { - pkg: 'sensor_msgs', - type: 'JointState', - arrayType: Float64Array, - property: 'position', - values: [ - { - header: { - stamp: { sec: 123456, nanosec: 789 }, - frame_id: 'main frame', + // similar to the above test, this requires introspection into the message by using the + // .hasMember method. The new bindings only support typed arrays so these tests are not + // really needed. + if (!useRosIdl) { + [ + /* eslint-disable camelcase */ + /* eslint-disable key-spacing */ + /* eslint-disable comma-spacing */ + { + pkg: 'sensor_msgs', + type: 'PointCloud2', + arrayType: Uint8Array, + property: 'data', + values: [ + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + height: 240, + width: 320, + fields: [], + is_bigendian: false, + point_step: 16, + row_step: 320 * 16, + data: uint8Data, + is_dense: false, }, - name: ['Tom', 'Jerry'], - velocity: [2, 3], - effort: [4, 5, 6], - position: float64Data, - }, - { - header: { - stamp: { sec: 123456, nanosec: 789 }, - frame_id: 'main frame', + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + height: 240, + width: 320, + fields: [], + is_bigendian: false, + point_step: 16, + row_step: 320 * 16, + data: Uint8Array.from(uint8Data), + is_dense: false, }, - name: ['Tom', 'Jerry'], - velocity: [2, 3], - effort: [4, 5, 6], - position: Float64Array.from(float64Data), - }, - { - header: { - stamp: { sec: 123456, nanosec: 789 }, - frame_id: 'main frame', + ], + }, + { + pkg: 'sensor_msgs', + type: 'Image', + arrayType: Uint8Array, + property: 'data', + values: [ + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + height: 240, + width: 320, + encoding: 'rgba', + is_bigendian: false, + step: 320 * 16, + is_dense: false, + data: uint8Data, }, - name: ['Tom', 'Jerry'], - velocity: [2, 3], - effort: [4, 5, 6], - position: Float64Array.from(Float64Array.from(float64Data)), - }, - ], - }, - /* eslint-enable camelcase */ - /* eslint-enable key-spacing */ - /* eslint-enable comma-spacing */ - ].forEach((testData) => { - const topic = testData.topic || 'topic' + testData.type; - testData.values.forEach((v, i) => { - it( - 'Make sure ' + testData.type + ' use TypedArray' + ', case ' + i, - function () { - const MessageType = rclnodejs.require( - testData.pkg + '/msg/' + testData.type - ); - const msg = translator.toROSMessage(MessageType, v); - assert(isTypedArray(msg[testData.property])); - assert(msg[testData.property] instanceof testData.arrayType); + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + height: 240, + width: 320, + encoding: 'rgba', + is_bigendian: false, + step: 320 * 16, + is_dense: false, + data: Uint8Array.from(uint8Data), + }, + ], + }, + { + pkg: 'sensor_msgs', + type: 'CompressedImage', + arrayType: Uint8Array, + property: 'data', + values: [ + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + format: 'jpeg', + data: uint8Data, + }, + { + header: { stamp: { sec: 11223, nanosec: 44556 }, frame_id: 'f001' }, + format: 'jpeg', + data: Uint8Array.from(uint8Data), + }, + ], + }, + { + pkg: 'sensor_msgs', + type: 'ChannelFloat32', + arrayType: Float32Array, + property: 'values', + values: [ + { name: 'intensity', values: float32Data }, + { name: 'intensity', values: Float32Array.from(float32Data) }, + { + name: 'intensity', + values: Float32Array.from(Float32Array.from(float32Data)), + }, + ], + }, + { + pkg: 'sensor_msgs', + type: 'JointState', + arrayType: Float64Array, + property: 'position', + values: [ + { + header: { + stamp: { sec: 123456, nanosec: 789 }, + frame_id: 'main frame', + }, + name: ['Tom', 'Jerry'], + velocity: [2, 3], + effort: [4, 5, 6], + position: float64Data, + }, + { + header: { + stamp: { sec: 123456, nanosec: 789 }, + frame_id: 'main frame', + }, + name: ['Tom', 'Jerry'], + velocity: [2, 3], + effort: [4, 5, 6], + position: Float64Array.from(float64Data), + }, + { + header: { + stamp: { sec: 123456, nanosec: 789 }, + frame_id: 'main frame', + }, + name: ['Tom', 'Jerry'], + velocity: [2, 3], + effort: [4, 5, 6], + position: Float64Array.from(Float64Array.from(float64Data)), + }, + ], + }, + /* eslint-enable camelcase */ + /* eslint-enable key-spacing */ + /* eslint-enable comma-spacing */ + ].forEach((testData) => { + const topic = testData.topic || 'topic' + testData.type; + testData.values.forEach((v, i) => { + it( + 'Make sure ' + testData.type + ' use TypedArray' + ', case ' + i, + function () { + const MessageType = rclnodejs.require( + testData.pkg + '/msg/' + testData.type + ); + const msg = translator.toROSMessage(MessageType, v); + assert(isTypedArray(msg[testData.property])); + assert(msg[testData.property] instanceof testData.arrayType); - msg[testData.property] = v[testData.property]; - assert(isTypedArray(msg[testData.property])); - assert(msg[testData.property] instanceof testData.arrayType); + msg[testData.property] = v[testData.property]; + assert(isTypedArray(msg[testData.property])); + assert(msg[testData.property] instanceof testData.arrayType); - const msg2 = new MessageType(); - assert(isTypedArray(msg2[testData.property])); - assert(msg2[testData.property] instanceof testData.arrayType); - } - ); + const msg2 = new MessageType(); + assert(isTypedArray(msg2[testData.property])); + assert(msg2[testData.property] instanceof testData.arrayType); + } + ); + }); }); - }); - const arrayLength = 1024; - [ - /* eslint-disable max-len */ - { - type: 'ByteMultiArray', - arrayType: Uint8Array, - values: arrayGen.generateValues( - Uint8Array, - arrayLength, - 256, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'Float32MultiArray', - arrayType: Float32Array, - values: arrayGen.generateValues( - Float32Array, - arrayLength, - 10000, - arrayGen.negative, - arrayGen.noRound - ), - }, - { - type: 'Float64MultiArray', - arrayType: Float64Array, - values: arrayGen.generateValues( - Float64Array, - arrayLength, - 10000, - arrayGen.negative, - arrayGen.noRound - ), - }, - { - type: 'Int8MultiArray', - arrayType: Int8Array, - values: arrayGen.generateValues( - Int8Array, - arrayLength, - 128, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'Int16MultiArray', - arrayType: Int16Array, - values: arrayGen.generateValues( - Int16Array, - arrayLength, - 32768, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'Int32MultiArray', - arrayType: Int32Array, - values: arrayGen.generateValues( - Int32Array, - arrayLength, - 2147483648, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'UInt8MultiArray', - arrayType: Uint8Array, - values: arrayGen.generateValues( - Uint8Array, - arrayLength, - 256, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'UInt16MultiArray', - arrayType: Uint16Array, - values: arrayGen.generateValues( - Uint16Array, - arrayLength, - 65536, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'UInt32MultiArray', - arrayType: Uint32Array, - values: arrayGen.generateValues( - Uint32Array, - arrayLength, - 4294967296, - arrayGen.positive, - Math.floor - ), - }, + const arrayLength = 1024; + [ + /* eslint-disable max-len */ + { + type: 'ByteMultiArray', + arrayType: Uint8Array, + values: arrayGen.generateValues( + Uint8Array, + arrayLength, + 256, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'Float32MultiArray', + arrayType: Float32Array, + values: arrayGen.generateValues( + Float32Array, + arrayLength, + 10000, + arrayGen.negative, + arrayGen.noRound + ), + }, + { + type: 'Float64MultiArray', + arrayType: Float64Array, + values: arrayGen.generateValues( + Float64Array, + arrayLength, + 10000, + arrayGen.negative, + arrayGen.noRound + ), + }, + { + type: 'Int8MultiArray', + arrayType: Int8Array, + values: arrayGen.generateValues( + Int8Array, + arrayLength, + 128, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'Int16MultiArray', + arrayType: Int16Array, + values: arrayGen.generateValues( + Int16Array, + arrayLength, + 32768, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'Int32MultiArray', + arrayType: Int32Array, + values: arrayGen.generateValues( + Int32Array, + arrayLength, + 2147483648, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'UInt8MultiArray', + arrayType: Uint8Array, + values: arrayGen.generateValues( + Uint8Array, + arrayLength, + 256, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'UInt16MultiArray', + arrayType: Uint16Array, + values: arrayGen.generateValues( + Uint16Array, + arrayLength, + 65536, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'UInt32MultiArray', + arrayType: Uint32Array, + values: arrayGen.generateValues( + Uint32Array, + arrayLength, + 4294967296, + arrayGen.positive, + Math.floor + ), + }, - { - type: 'ByteMultiArray', - arrayType: Uint8Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 256, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'Float32MultiArray', - arrayType: Float32Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 10000, - arrayGen.negative, - arrayGen.noRound - ), - }, - { - type: 'Float64MultiArray', - arrayType: Float64Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 10000, - arrayGen.negative, - arrayGen.noRound - ), - }, - { - type: 'Int8MultiArray', - arrayType: Int8Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 128, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'Int16MultiArray', - arrayType: Int16Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 32768, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'Int32MultiArray', - arrayType: Int32Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 2147483648, - arrayGen.negative, - Math.floor - ), - }, - { - type: 'UInt8MultiArray', - arrayType: Uint8Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 256, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'UInt16MultiArray', - arrayType: Uint16Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 65536, - arrayGen.positive, - Math.floor - ), - }, - { - type: 'UInt32MultiArray', - arrayType: Uint32Array, - values: arrayGen.generateValues( - Array, - arrayLength, - 4294967296, - arrayGen.positive, - Math.floor - ), - }, - /* eslint-enable max-len */ - ].forEach((testData) => { - const topic = testData.topic || 'topic' + testData.type; - it('Make sure ' + testData.type + ' use TypedArray', function () { - const MessageType = rclnodejs.require('std_msgs/msg/' + testData.type); - const msg = translator.toROSMessage(MessageType, { - layout: { - dim: [{ label: 'length', size: 0, stride: 0 }], - // eslint-disable-next-line - data_offset: 0, - }, - data: testData.values, - }); - assert(isTypedArray(msg.data)); - assert(msg.data instanceof testData.arrayType); + { + type: 'ByteMultiArray', + arrayType: Uint8Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 256, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'Float32MultiArray', + arrayType: Float32Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 10000, + arrayGen.negative, + arrayGen.noRound + ), + }, + { + type: 'Float64MultiArray', + arrayType: Float64Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 10000, + arrayGen.negative, + arrayGen.noRound + ), + }, + { + type: 'Int8MultiArray', + arrayType: Int8Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 128, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'Int16MultiArray', + arrayType: Int16Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 32768, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'Int32MultiArray', + arrayType: Int32Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 2147483648, + arrayGen.negative, + Math.floor + ), + }, + { + type: 'UInt8MultiArray', + arrayType: Uint8Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 256, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'UInt16MultiArray', + arrayType: Uint16Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 65536, + arrayGen.positive, + Math.floor + ), + }, + { + type: 'UInt32MultiArray', + arrayType: Uint32Array, + values: arrayGen.generateValues( + Array, + arrayLength, + 4294967296, + arrayGen.positive, + Math.floor + ), + }, + /* eslint-enable max-len */ + ].forEach((testData) => { + const topic = testData.topic || 'topic' + testData.type; + it('Make sure ' + testData.type + ' use TypedArray', function () { + const MessageType = rclnodejs.require('std_msgs/msg/' + testData.type); + const msg = translator.toROSMessage(MessageType, { + layout: { + dim: [{ label: 'length', size: 0, stride: 0 }], + // eslint-disable-next-line + data_offset: 0, + }, + data: testData.values, + }); + assert(isTypedArray(msg.data)); + assert(msg.data instanceof testData.arrayType); - msg.data = testData.values; - assert(isTypedArray(msg.data)); - assert(msg.data instanceof testData.arrayType); + msg.data = testData.values; + assert(isTypedArray(msg.data)); + assert(msg.data instanceof testData.arrayType); - const msg2 = new MessageType(); - assert(isTypedArray(msg2.data)); - assert(msg2.data instanceof testData.arrayType); + const msg2 = new MessageType(); + assert(isTypedArray(msg2.data)); + assert(msg2.data instanceof testData.arrayType); + }); }); - }); + } }); diff --git a/test/test-bounded-sequences.js b/test/test-bounded-sequences.js index 3bb655ff..88afada2 100644 --- a/test/test-bounded-sequences.js +++ b/test/test-bounded-sequences.js @@ -63,7 +63,7 @@ describe('Test bounded sequeces', function () { const expected = { bool_values: [true, false], byte_values: Uint8Array.from([127, 125]), - char_values: Int8Array.from([127, 125]), + char_values: Int8Array.from([127, 125]), // char[] is uint8_t[] in ROS, the old serialization mistakenly deserialized it as Int8Array float32_values: Float32Array.from([1.1, 2.2, 3.3]), float64_values: Float64Array.from([1.1, 2.2]), int8_values: Int8Array.from([1, 2]), @@ -120,7 +120,107 @@ describe('Test bounded sequeces', function () { 'bounded_sequences', (response) => { clearInterval(timer); - assert.deepEqual(response, expected); + assert.deepStrictEqual(response.bool_values, expected.bool_values); + assert.deepStrictEqual(response.byte_values, expected.byte_values); + assert.deepStrictEqual( + Array.from(response.char_values), + Array.from(expected.char_values) + ); + assert.deepStrictEqual( + response.float32_values, + expected.float32_values + ); + assert.deepStrictEqual( + response.float64_values, + expected.float64_values + ); + assert.deepStrictEqual(response.int8_values, expected.int8_values); + assert.deepStrictEqual(response.uint8_values, expected.uint8_values); + assert.deepStrictEqual(response.int16_values, expected.int16_values); + assert.deepStrictEqual(response.uint16_values, expected.uint16_values); + assert.deepStrictEqual(response.int32_values, expected.int32_values); + assert.deepStrictEqual(response.uint32_values, expected.uint32_values); + assert.deepStrictEqual( + Array.from(response.int64_values).map((i) => Number(i)), + expected.int64_values + ); + assert.deepStrictEqual( + Array.from(response.uint64_values).map((i) => Number(i)), + expected.uint64_values + ); + assert.deepStrictEqual( + Array.from(response.int64_values_default).map((i) => Number(i)), + expected.int64_values_default + ); + assert.deepStrictEqual( + Array.from(response.uint64_values_default).map((i) => Number(i)), + expected.uint64_values_default + ); + assert.deepStrictEqual(response.string_values, expected.string_values); + assert.deepStrictEqual( + response.basic_types_values, + expected.basic_types_values + ); + assert.deepStrictEqual( + response.bool_values_default, + expected.bool_values_default + ); + assert.deepStrictEqual( + response.byte_values_default, + expected.byte_values_default + ); + assert.deepStrictEqual( + Array.from(response.char_values_default), + Array.from(expected.char_values_default) + ); + assert.deepStrictEqual( + response.float32_values_default, + expected.float32_values_default + ); + assert.deepStrictEqual( + response.float64_values_default, + expected.float64_values_default + ); + assert.deepStrictEqual( + response.int16_values_default, + expected.int16_values_default + ); + assert.deepStrictEqual( + response.int32_values_default, + expected.int32_values_default + ); + assert.deepStrictEqual( + response.int8_values_default, + expected.int8_values_default + ); + assert.deepStrictEqual( + response.string_values_default, + expected.string_values_default + ); + assert.deepStrictEqual( + response.uint16_values_default, + expected.uint16_values_default + ); + assert.deepStrictEqual( + response.uint32_values_default, + expected.uint32_values_default + ); + assert.deepStrictEqual( + response.uint8_values_default, + expected.uint8_values_default + ); + assert.deepStrictEqual( + response.alignment_check, + expected.alignment_check + ); + assert.deepStrictEqual( + response.constants_values, + expected.constants_values + ); + assert.deepStrictEqual( + response.defaults_values, + expected.defaults_values + ); node.destroy(); done(); } diff --git a/test/test-compound-msg-type-check.js b/test/test-compound-msg-type-check.js index 721408dc..f176a1f2 100644 --- a/test/test-compound-msg-type-check.js +++ b/test/test-compound-msg-type-check.js @@ -17,6 +17,7 @@ const assert = require('assert'); const rclnodejs = require('../index.js'); const assertThrowsError = require('./utils.js').assertThrowsError; +const { useRosIdl } = require('../options'); describe('Compound types', function () { this.timeout(60 * 1000); @@ -40,17 +41,20 @@ describe('Compound types', function () { assert.deepStrictEqual(typeof msg.a, 'undefined'); }); - it('Array', function () { - const Byte = rclnodejs.require('std_msgs').msg.Byte; - const ByteArray = Byte.ArrayType; - let msg = new ByteArray(3); - msg.fill([1, 2, 3]); + // there is no special array wrappers in the new bindings + if (!useRosIdl) { + it('Array', function () { + const Byte = rclnodejs.require('std_msgs').msg.Byte; + const ByteArray = Byte.ArrayType; + let msg = new ByteArray(3); + msg.fill([1, 2, 3]); - assert.deepStrictEqual(msg.data.length, 3); - assert.deepStrictEqual(msg.data[0], 1); - assert.deepStrictEqual(msg.data[1], 2); - assert.deepStrictEqual(msg.data[2], 3); - }); + assert.deepStrictEqual(msg.data.length, 3); + assert.deepStrictEqual(msg.data[0], 1); + assert.deepStrictEqual(msg.data[1], 2); + assert.deepStrictEqual(msg.data[2], 3); + }); + } it('Object with Header', function () { const Header = rclnodejs.require('std_msgs').msg.Header; @@ -60,7 +64,12 @@ describe('Compound types', function () { assert.ok('frame_id' in header); assert.deepStrictEqual(typeof header.stamp, 'object'); - assert.deepStrictEqual(typeof header.frame_id, 'undefined'); + // the new bindings correctly initialize strings as an empty string instead of undefined. + if (useRosIdl) { + assert.deepStrictEqual(typeof header.frame_id, 'string'); + } else { + assert.deepStrictEqual(typeof header.frame_id, 'undefined'); + } }); it('Complex object', function () { diff --git a/test/test-cross-lang.js b/test/test-cross-lang.js index 1a63f289..9d2e1d72 100644 --- a/test/test-cross-lang.js +++ b/test/test-cross-lang.js @@ -20,6 +20,7 @@ const childProcess = require('child_process'); const rclnodejs = require('../index.js'); const utils = require('./utils.js'); const kill = require('tree-kill'); +const { useRosIdl } = require('../options'); describe('Cross-language interaction', function () { this.timeout(60 * 1000); @@ -106,7 +107,11 @@ describe('Cross-language interaction', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -135,7 +140,11 @@ describe('Cross-language interaction', function () { var msg = text; var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); diff --git a/test/test-default-messages.js b/test/test-default-messages.js new file mode 100644 index 00000000..ca38ba23 --- /dev/null +++ b/test/test-default-messages.js @@ -0,0 +1,115 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +'use strict'; + +const assert = require('assert'); +const rclnodejs = require('../index.js'); + +describe('rclnodejs message communication', function () { + this.timeout(60 * 1000); + + before(function () { + return rclnodejs.init(); + }); + + after(function () { + rclnodejs.shutdown(); + }); + + it('should publish messages with unfilled defaults', function (done) { + const publisherNode = rclnodejs.createNode('defaults_message_publisher'); + const subscriptionNode = rclnodejs.createNode( + 'defaults_message_subscriber' + ); + + const subscription = subscriptionNode.createSubscription( + 'test_msgs/msg/Defaults', + 'defaults_message_channel1', + (msg) => { + timer.cancel(); + assert.strictEqual(msg.bool_value, true); + assert.strictEqual(msg.byte_value, 50); + assert.strictEqual(msg.char_value, 100); + assert.strictEqual(msg.float32_value, 1.125); + assert.strictEqual(msg.float64_value, 1.125); + assert.strictEqual(msg.int8_value, -50); + assert.strictEqual(msg.uint8_value, 200); + assert.strictEqual(msg.int16_value, -1000); + assert.strictEqual(msg.uint16_value, 2000); + assert.strictEqual(msg.int32_value, -30000); + assert.strictEqual(msg.uint32_value, 60000); + assert.strictEqual(msg.int64_value, -40000000); + assert.strictEqual(msg.uint64_value, 50000000); + publisherNode.destroy(); + subscriptionNode.destroy(); + done(); + } + ); + + const publisher = publisherNode.createPublisher( + 'test_msgs/msg/Defaults', + 'defaults_message_channel1' + ); + const timer = publisherNode.createTimer(100, () => { + publisher.publish({}); + }); + rclnodejs.spin(subscriptionNode); + rclnodejs.spin(publisherNode); + }); + + it('overwrites the default values when it is provided', function (done) { + const publisherNode = rclnodejs.createNode('defaults_message_publisher'); + const subscriptionNode = rclnodejs.createNode( + 'defaults_message_subscriber' + ); + + const subscription = subscriptionNode.createSubscription( + 'test_msgs/msg/Defaults', + 'defaults_message_channel2', + (msg) => { + timer.cancel(); + assert.strictEqual(msg.bool_value, true); + assert.strictEqual(msg.byte_value, 50); + assert.strictEqual(msg.char_value, 100); + assert.strictEqual(msg.float32_value, 1.125); + assert.strictEqual(msg.float64_value, 1.125); + assert.strictEqual(msg.int8_value, -51); + assert.strictEqual(msg.uint8_value, 200); + assert.strictEqual(msg.int16_value, -1000); + assert.strictEqual(msg.uint16_value, 2000); + assert.strictEqual(msg.int32_value, -30000); + assert.strictEqual(msg.uint32_value, 60000); + assert.strictEqual(msg.int64_value, -40000000); + assert.strictEqual(msg.uint64_value, 50000000); + publisherNode.destroy(); + subscriptionNode.destroy(); + done(); + } + ); + + const publisher = publisherNode.createPublisher( + 'test_msgs/msg/Defaults', + 'defaults_message_channel2' + ); + const timer = publisherNode.createTimer(100, () => { + publisher.publish({ int8_value: -51 }); + }); + rclnodejs.spin(subscriptionNode); + rclnodejs.spin(publisherNode); + }); +}); diff --git a/test/test-disable-typedarray.js b/test/test-disable-typedarray.js index 11c959b9..8887690b 100644 --- a/test/test-disable-typedarray.js +++ b/test/test-disable-typedarray.js @@ -16,184 +16,188 @@ const assert = require('assert'); const rclnodejs = require('../index.js'); +const { useRosIdl } = require('../options'); /* eslint-disable camelcase */ /* eslint-disable key-spacing */ /* eslint-disable comma-spacing */ -describe('rclnodejs message communication', function () { - this.timeout(60 * 1000); +// rosidl generator only supports typed array +if (!useRosIdl) { + describe('rclnodejs message communication', function () { + this.timeout(60 * 1000); - before(function () { - return rclnodejs.init(); - }); - - after(function () { - rclnodejs.shutdown(); - }); - - it('disable TypedArray in topic', function (done) { - const msg = { - header: { - stamp: { - sec: 123456, - nanosec: 789, - }, - frame_id: 'main frame', - }, - name: ['Tom', 'Jerry'], - position: [1, 2], - velocity: [2, 3], - effort: [4, 5, 6], - }; - - let node = rclnodejs.createNode('disable_typedarray'); - let timer = setInterval(() => { - let publisher = node.createPublisher( - 'sensor_msgs/msg/JointState', - 'JointState' - ); - assert.doesNotThrow(() => { - publisher.publish(msg); - }, RangeError); - }, 100); + before(function () { + return rclnodejs.init(); + }); - node.createSubscription( - 'sensor_msgs/msg/JointState', - 'JointState', - { enableTypedArray: false }, - (response) => { - clearInterval(timer); - assert.deepStrictEqual(response, msg); - node.destroy(); - done(); - } - ); - rclnodejs.spin(node); - }); + after(function () { + rclnodejs.shutdown(); + }); - it('disable TypedArray in response', function (done) { - const mapData = { - map: { + it('disable TypedArray in topic', function (done) { + const msg = { header: { stamp: { sec: 123456, nanosec: 789, }, - frame_id: 'main_frame', + frame_id: 'main frame', }, - info: { - map_load_time: { - sec: 123456, - nanosec: 789, + name: ['Tom', 'Jerry'], + position: [1, 2], + velocity: [2, 3], + effort: [4, 5, 6], + }; + + let node = rclnodejs.createNode('disable_typedarray'); + let timer = setInterval(() => { + let publisher = node.createPublisher( + 'sensor_msgs/msg/JointState', + 'JointState' + ); + assert.doesNotThrow(() => { + publisher.publish(msg); + }, RangeError); + }, 100); + + node.createSubscription( + 'sensor_msgs/msg/JointState', + 'JointState', + { enableTypedArray: false }, + (response) => { + clearInterval(timer); + assert.deepStrictEqual(response, msg); + node.destroy(); + done(); + } + ); + rclnodejs.spin(node); + }); + + it('disable TypedArray in response', function (done) { + const mapData = { + map: { + header: { + stamp: { + sec: 123456, + nanosec: 789, + }, + frame_id: 'main_frame', }, - resolution: 1.0, - width: 1024, - height: 768, - origin: { - position: { - x: 0.0, - y: 0.0, - z: 0.0, + info: { + map_load_time: { + sec: 123456, + nanosec: 789, }, - orientation: { - x: 0.0, - y: 0.0, - z: 0.0, - w: 0.0, + resolution: 1.0, + width: 1024, + height: 768, + origin: { + position: { + x: 0.0, + y: 0.0, + z: 0.0, + }, + orientation: { + x: 0.0, + y: 0.0, + z: 0.0, + w: 0.0, + }, }, }, + data: [1, 2, 3], }, - data: [1, 2, 3], - }, - }; - const node = rclnodejs.createNode('disable_typedarray'); + }; + const node = rclnodejs.createNode('disable_typedarray'); - node.createService('nav_msgs/srv/GetMap', 'get_map', () => { - return mapData; - }); + node.createService('nav_msgs/srv/GetMap', 'get_map', () => { + return mapData; + }); - rclnodejs.spin(node); - const client = node.createClient('nav_msgs/srv/GetMap', 'get_map', { - enableTypedArray: false, - }); - client.sendRequest({}, (response) => { - assert.deepStrictEqual(response, mapData); - node.destroy(); - done(); + rclnodejs.spin(node); + const client = node.createClient('nav_msgs/srv/GetMap', 'get_map', { + enableTypedArray: false, + }); + client.sendRequest({}, (response) => { + assert.deepStrictEqual(response, mapData); + node.destroy(); + done(); + }); }); - }); - it('disable TypedArray in request', function (done) { - const mapData = { - map: { - header: { - stamp: { - sec: 123456, - nanosec: 789, - }, - frame_id: 'main_frame', - }, - info: { - map_load_time: { - sec: 123456, - nanosec: 789, + it('disable TypedArray in request', function (done) { + const mapData = { + map: { + header: { + stamp: { + sec: 123456, + nanosec: 789, + }, + frame_id: 'main_frame', }, - resolution: 1.0, - width: 1024, - height: 768, - origin: { - position: { - x: 0.0, - y: 0.0, - z: 0.0, + info: { + map_load_time: { + sec: 123456, + nanosec: 789, }, - orientation: { - x: 0.0, - y: 0.0, - z: 0.0, - w: 0.0, + resolution: 1.0, + width: 1024, + height: 768, + origin: { + position: { + x: 0.0, + y: 0.0, + z: 0.0, + }, + orientation: { + x: 0.0, + y: 0.0, + z: 0.0, + w: 0.0, + }, }, }, + data: [1, 2, 3], }, - data: [1, 2, 3], - }, - initial_pose: { - header: { - stamp: { - sec: 123456, - nanosec: 789, + initial_pose: { + header: { + stamp: { + sec: 123456, + nanosec: 789, + }, + frame_id: 'main frame', }, - frame_id: 'main frame', - }, - pose: { pose: { - position: { x: 11.5, y: 112.75, z: 9.0 }, - orientation: { x: 31.5, y: 21.5, z: 7.5, w: 1.5 }, + pose: { + position: { x: 11.5, y: 112.75, z: 9.0 }, + orientation: { x: 31.5, y: 21.5, z: 7.5, w: 1.5 }, + }, + covariance: Array.from({ length: 36 }, (v, k) => k), }, - covariance: Array.from({ length: 36 }, (v, k) => k), }, - }, - }; + }; - const node = rclnodejs.createNode('array_client'); - node.createService( - 'nav_msgs/srv/SetMap', - 'set_map', - { enableTypedArray: false }, - (request, response) => { - assert.deepStrictEqual(request, mapData); - let result = response.template; - result.success = true; - response.send(result); - } - ); + const node = rclnodejs.createNode('array_client'); + node.createService( + 'nav_msgs/srv/SetMap', + 'set_map', + { enableTypedArray: false }, + (request, response) => { + assert.deepStrictEqual(request, mapData); + let result = response.template; + result.success = true; + response.send(result); + } + ); - rclnodejs.spin(node); - const client = node.createClient('nav_msgs/srv/SetMap', 'set_map'); - client.sendRequest(mapData, (response) => { - assert.deepStrictEqual(response.success, true); - node.destroy(); - done(); + rclnodejs.spin(node); + const client = node.createClient('nav_msgs/srv/SetMap', 'set_map'); + client.sendRequest(mapData, (response) => { + assert.deepStrictEqual(response.success, true); + node.destroy(); + done(); + }); }); }); -}); +} diff --git a/test/test-fixed-array.js b/test/test-fixed-array.js deleted file mode 100644 index 234f4bfc..00000000 --- a/test/test-fixed-array.js +++ /dev/null @@ -1,134 +0,0 @@ -// Copyright (c) 2018 Intel Corporation. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -'use strict'; - -const assert = require('assert'); -const rclnodejs = require('../index.js'); - -/* eslint-disable camelcase */ -/* eslint-disable key-spacing */ -/* eslint-disable comma-spacing */ - -describe('Test message which has a fixed array of 36', function () { - this.timeout(60 * 1000); - - const mapData = { - map: { - header: { - stamp: { - sec: 123456, - nanosec: 789, - }, - frame_id: 'main_frame', - }, - info: { - map_load_time: { - sec: 123456, - nanosec: 789, - }, - resolution: 1.0, - width: 1024, - height: 768, - origin: { - position: { - x: 0.0, - y: 0.0, - z: 0.0, - }, - orientation: { - x: 0.0, - y: 0.0, - z: 0.0, - w: 0.0, - }, - }, - }, - data: Int8Array.from([1, 2, 3]), - }, - initial_pose: { - header: { - stamp: { - sec: 123456, - nanosec: 789, - }, - frame_id: 'main frame', - }, - pose: { - pose: { - position: { x: 11.5, y: 112.75, z: 9.0 }, - orientation: { x: 31.5, y: 21.5, z: 7.5, w: 1.5 }, - }, - covariance: Float64Array.from({ length: 36 }, (v, k) => k), - }, - }, - }; - - before(function () { - return rclnodejs.init(); - }); - - after(function () { - rclnodejs.shutdown(); - }); - - it('Assigned with an array of 36', function (done) { - const node = rclnodejs.createNode('set_map_client'); - node.createService( - 'nav_msgs/srv/SetMap', - 'set_map', - (request, response) => { - assert.deepStrictEqual(request, mapData); - response.success = true; - return response; - } - ); - - rclnodejs.spin(node); - const client = node.createClient('nav_msgs/srv/SetMap', 'set_map'); - client.sendRequest(mapData, (response) => { - assert.deepStrictEqual(response.success, true); - node.destroy(); - done(); - }); - }); - - it('Assigned with a longer array', function (done) { - mapData.initial_pose.pose.covariance = Float64Array.from( - { length: 37 }, - (v, k) => k - ); - const node = rclnodejs.createNode('set_map_client'); - const client = node.createClient('nav_msgs/srv/SetMap', 'set_map'); - assert.throws(() => { - client.sendRequest(mapData, (response) => {}); - }, RangeError); - node.destroy(); - done(); - }); - - it('Assigned with a shorter array', function (done) { - mapData.initial_pose.pose.covariance = Float64Array.from( - { length: 35 }, - (v, k) => k - ); - const node = rclnodejs.createNode('set_map_client'); - const client = node.createClient('nav_msgs/srv/SetMap', 'set_map'); - assert.throws(() => { - client.sendRequest(mapData, (response) => {}); - }, RangeError); - node.destroy(); - done(); - }); -}); diff --git a/test/test-fixed-arrays.js b/test/test-fixed-arrays.js new file mode 100644 index 00000000..88829ca5 --- /dev/null +++ b/test/test-fixed-arrays.js @@ -0,0 +1,142 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +'use strict'; + +const assert = require('assert'); +const rclnodejs = require('../index.js'); + +describe('rclnodejs message communication', function () { + this.timeout(60 * 1000); + + before(function () { + return rclnodejs.init(); + }); + + after(function () { + rclnodejs.shutdown(); + }); + + it('should publish messages with fixed arrays', function (done) { + const publisherNode = rclnodejs.createNode('fixed_arrays_publisher'); + const subscriptionNode = rclnodejs.createNode('fixed_arrays_subscriber'); + const originalMsg = { + bool_values: [true, true, false], + byte_values: [0, 1, 2], + char_values: [0, 1, 2], + float32_values: [0, 1, 2], + float64_values: [0, 1, 2], + int8_values: [0, 1, 2], + uint8_values: [0, 1, 2], + int16_values: [0, 1, 2], + uint16_values: [0, 1, 2], + int32_values: [0, 1, 2], + uint32_values: [0, 1, 2], + int64_values: [0, 1, 2], + uint64_values: [0, 1, 2], + string_values: ['a', 'b', 'c'], + basic_types_values: [{}, {}, {}], + constants_values: [{}, {}, {}], + defaults_values: [{}, {}, {}], + alignment_check: 0, + }; + + const subscription = subscriptionNode.createSubscription( + 'test_msgs/msg/Arrays', + 'fixed_arrays_channel1', + (msg) => { + timer.cancel(); + assert.deepStrictEqual( + Array.from(msg.bool_values), + originalMsg.bool_values + ); + assert.deepStrictEqual( + Array.from(msg.byte_values), + originalMsg.byte_values + ); + assert.deepStrictEqual( + Array.from(msg.char_values), + originalMsg.char_values + ); + assert.deepStrictEqual( + Array.from(msg.float32_values), + originalMsg.float32_values + ); + assert.deepStrictEqual( + Array.from(msg.float64_values), + originalMsg.float64_values + ); + assert.deepStrictEqual( + Array.from(msg.int8_values), + originalMsg.int8_values + ); + assert.deepStrictEqual( + Array.from(msg.uint8_values), + originalMsg.uint8_values + ); + assert.deepStrictEqual( + Array.from(msg.int16_values), + originalMsg.int16_values + ); + assert.deepStrictEqual( + Array.from(msg.uint16_values), + originalMsg.uint16_values + ); + assert.deepStrictEqual( + Array.from(msg.int32_values), + originalMsg.int32_values + ); + assert.deepStrictEqual( + Array.from(msg.uint32_values), + originalMsg.uint32_values + ); + assert.deepStrictEqual( + Array.from(msg.int64_values).map((i) => Number(i)), + originalMsg.int64_values + ); + assert.deepStrictEqual( + Array.from(msg.int64_values).map((i) => Number(i)), + originalMsg.uint64_values + ); + assert.deepStrictEqual( + Array.from(msg.string_values), + originalMsg.string_values + ); + assert.strictEqual(msg.alignment_check, 0); + assert.strictEqual(msg.defaults_values[0].bool_value, true); + assert.strictEqual(msg.defaults_values[1].bool_value, true); + assert.strictEqual(msg.defaults_values[2].bool_value, true); + assert.strictEqual(msg.defaults_values[0].int8_value, -50); + assert.strictEqual(msg.defaults_values[1].int8_value, -50); + assert.strictEqual(msg.defaults_values[2].int8_value, -50); + publisherNode.destroy(); + subscriptionNode.destroy(); + done(); + } + ); + + const publisher = publisherNode.createPublisher( + 'test_msgs/msg/Arrays', + 'fixed_arrays_channel1' + ); + const timer = publisherNode.createTimer(100, () => { + publisher.publish(originalMsg); + }); + rclnodejs.spin(subscriptionNode); + rclnodejs.spin(publisherNode); + }); +}); diff --git a/test/test-lifecycle-publisher.js b/test/test-lifecycle-publisher.js index 688e1e9f..ab0e86d3 100644 --- a/test/test-lifecycle-publisher.js +++ b/test/test-lifecycle-publisher.js @@ -97,22 +97,22 @@ describe('LifecyclePublisher test suite', function () { } ); - lifecyclePublisher.publish(TEST_MSG); + lifecyclePublisher.publish({ data: TEST_MSG }); await assertUtils.createDelay(waitTime); assert.strictEqual(cbCnt, 0); lifecyclePublisher.activate(); - lifecyclePublisher.publish(TEST_MSG); + lifecyclePublisher.publish({ data: TEST_MSG }); await assertUtils.createDelay(waitTime); assert.strictEqual(cbCnt, 1); lifecyclePublisher.deactivate(); - lifecyclePublisher.publish(TEST_MSG); + lifecyclePublisher.publish({ data: TEST_MSG }); await assertUtils.createDelay(waitTime); assert.strictEqual(cbCnt, 1); lifecyclePublisher.activate(); - lifecyclePublisher.publish(TEST_MSG); + lifecyclePublisher.publish({ data: TEST_MSG }); await assertUtils.createDelay(waitTime); assert.strictEqual(cbCnt, 2); }); diff --git a/test/test-message-object.js b/test/test-message-object.js index b0efc449..1e2da237 100644 --- a/test/test-message-object.js +++ b/test/test-message-object.js @@ -38,6 +38,10 @@ describe('Rclnodejs createMessage() testing', function () { let promises = []; installedPackagesRoot.forEach((path) => { let promise = packages.findPackagesInDirectory(path).then((pkgs) => { + if (useRosIdl) { + // this packages contains invalid messages + pkgs.delete('libstatistics_collector'); + } pkgs.forEach((pkg) => { pkg.messages.forEach((info) => { const s = @@ -179,6 +183,10 @@ describe('Rclnodejs createMessageObject() testing', function () { let promises = []; installedPackagesRoot.forEach((path) => { let promise = packages.findPackagesInDirectory(path).then((pkgs) => { + if (useRosIdl) { + // this packages contains invalid messages + pkgs.delete('libstatistics_collector'); + } pkgs.forEach((pkg) => { pkg.messages.forEach((info) => { const s = diff --git a/test/test-message-translator-primitive.js b/test/test-message-translator-primitive.js index 66c26010..31fd6499 100644 --- a/test/test-message-translator-primitive.js +++ b/test/test-message-translator-primitive.js @@ -17,6 +17,7 @@ const rclnodejs = require('../index.js'); const deepEqual = require('deep-equal'); const arrayGen = require('./array_generator.js'); +const { useRosIdl } = require('../options'); /* eslint-disable camelcase */ /* eslint-disable indent */ @@ -35,7 +36,7 @@ describe('Rclnodejs message translation: primitive types', function () { [ { type: 'Bool', values: [true, false] }, { type: 'Byte', values: [0, 1, 2, 3, 255] }, - { type: 'Char', values: [-128, -127, -2, -1, 0, 1, 2, 3, 127] }, + { type: 'Char', values: [0, 1, 2, 3, 127, 128, 255] }, // char is unsigned in ROS { type: 'Float32', values: [-5, 0, 1.25, 89.75, 72.5, 3.14e5] }, { type: 'Float64', values: [-5, 0, 1.25, 89.75, 72.5, 3.14159265358e8] }, { type: 'Int16', values: [-32768, -2, -1, 0, 1, 2, 3, 32767] }, @@ -103,7 +104,11 @@ describe('Rclnodejs message translation: primitive types', function () { ); } }); - publisher.publish(v); // Short-cut form of publishing primitive types + if (useRosIdl) { + publisher.publish({ data: v }); // Short-cut form not supported in rosidl generator + } else { + publisher.publish(v); // Short-cut form of publishing primitive types + } rclnodejs.spin(node); }); } diff --git a/test/test-message-type.js b/test/test-message-type.js index 5034a35e..730588de 100644 --- a/test/test-message-type.js +++ b/test/test-message-type.js @@ -71,7 +71,7 @@ describe('Rclnodejs message type testing', function () { const msgChar = 'std_msgs/msg/Char'; var publisher = childProcess.fork(`${__dirname}/publisher_msg.js`, [ 'Char', - '"A"', + '65', // char in uint8 in ROS ]); var subscription = node.createSubscription( msgChar, diff --git a/test/test-msg-type-cpp-node.js b/test/test-msg-type-cpp-node.js index 09bfa1c0..47746cc6 100644 --- a/test/test-msg-type-cpp-node.js +++ b/test/test-msg-type-cpp-node.js @@ -22,6 +22,7 @@ const childProcess = require('child_process'); const deepEqual = require('deep-equal'); const rclnodejs = require('../index.js'); const utils = require('./utils.js'); +const { useRosIdl } = require('../options'); describe('Rclnodejs - Cpp message type testing', function () { var cppSubscriptionPath = path.join(__dirname, 'cpp', 'subscription_msg'); @@ -59,7 +60,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -83,7 +88,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -107,7 +116,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -131,7 +144,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -156,7 +173,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -180,7 +201,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -204,7 +229,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -228,7 +257,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -252,7 +285,11 @@ describe('Rclnodejs - Cpp message type testing', function () { ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -275,7 +312,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -298,7 +339,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -322,7 +367,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -345,7 +394,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -368,7 +421,11 @@ describe('Rclnodejs - Cpp message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); diff --git a/test/test-msg-type-py-node.js b/test/test-msg-type-py-node.js index 8bbc93c6..9d0dd99b 100644 --- a/test/test-msg-type-py-node.js +++ b/test/test-msg-type-py-node.js @@ -21,6 +21,7 @@ const childProcess = require('child_process'); const deepEqual = require('deep-equal'); const rclnodejs = require('../index.js'); const utils = require('./utils.js'); +const { useRosIdl } = require('../options'); describe('Rclnodejs - Python message type testing', function () { this.timeout(60 * 1000); @@ -59,7 +60,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -87,7 +92,7 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + publisher.publish({ data: msg.charCodeAt(0) }); }); rclnodejs.spin(node); }); @@ -115,7 +120,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -143,7 +152,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -171,7 +184,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -199,7 +216,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -227,7 +248,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -255,7 +280,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -283,7 +312,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -311,7 +344,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -339,7 +376,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -367,7 +408,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -395,7 +440,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); @@ -423,7 +472,11 @@ describe('Rclnodejs - Python message type testing', function () { } ); var timer = node.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(node); }); diff --git a/test/test-multi-nodes.js b/test/test-multi-nodes.js index 8bd7c52f..5866a039 100644 --- a/test/test-multi-nodes.js +++ b/test/test-multi-nodes.js @@ -20,6 +20,7 @@ const childProcess = require('child_process'); const rclnodejs = require('../index.js'); const utils = require('./utils.js'); const kill = require('tree-kill'); +const { useRosIdl } = require('../options'); describe('Multiple nodes interation testing', function () { this.timeout(60 * 1000); @@ -69,7 +70,11 @@ describe('Multiple nodes interation testing', function () { ); var jsPublisher = node.createPublisher(RclString, 'js_pycpp_chatter'); setTimeout(() => { - jsPublisher.publish(msg); + if (useRosIdl) { + jsPublisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + jsPublisher.publish(msg); + } }, 1000); rclnodejs.spin(node); }); diff --git a/test/test-non-primitive-msg-type-check.js b/test/test-non-primitive-msg-type-check.js index f459b214..57c07a8c 100644 --- a/test/test-non-primitive-msg-type-check.js +++ b/test/test-non-primitive-msg-type-check.js @@ -16,6 +16,7 @@ const assert = require('assert'); const rclnodejs = require('../index.js'); +const { useRosIdl } = require('../options'); /* eslint-disable camelcase */ describe('Rclnodejs non primitive message type testing', function () { @@ -60,18 +61,27 @@ describe('Rclnodejs non primitive message type testing', function () { assert.deepStrictEqual(44556, jointStateClone.header.stamp.nanosec); assert.deepStrictEqual('1234567x', jointStateClone.header.frame_id); assert.deepStrictEqual(['Willy', 'Tacky'], jointStateClone.name); - assert.deepStrictEqual( - Float64Array.from([1, 7, 3, 4, 2, 2, 8]), - jointStateClone.position - ); - assert.deepStrictEqual( - Float64Array.from([8, 9, 6, 4]), - jointStateClone.velocity - ); - assert.deepStrictEqual( - Float64Array.from([1, 0, 2, 6, 7]), - jointStateClone.effort - ); + + // new bindings does not do conversion until serialization so it doesn't automatically + // converts number arrays to typed arrays on assignment. + if (useRosIdl) { + assert.deepStrictEqual([1, 7, 3, 4, 2, 2, 8], jointStateClone.position); + assert.deepStrictEqual([8, 9, 6, 4], jointStateClone.velocity); + assert.deepStrictEqual([1, 0, 2, 6, 7], jointStateClone.effort); + } else { + assert.deepStrictEqual( + Float64Array.from([1, 7, 3, 4, 2, 2, 8]), + jointStateClone.position + ); + assert.deepStrictEqual( + Float64Array.from([8, 9, 6, 4]), + jointStateClone.velocity + ); + assert.deepStrictEqual( + Float64Array.from([1, 0, 2, 6, 7]), + jointStateClone.effort + ); + } }); it('geometry_msgs/msg/Transform checking', function () { @@ -96,67 +106,80 @@ describe('Rclnodejs non primitive message type testing', function () { assert.deepStrictEqual(1.0, transformClone.rotation.w); }); - it('std_msgs/msg/Float32MultiArray checking', function () { - const Float32MultiArray = rclnodejs.require( - 'std_msgs/msg/Float32MultiArray' - ); - const MultiArrayDimension = rclnodejs.require( - 'std_msgs/msg/MultiArrayDimension' - ); - - let float32MultiArray = new Float32MultiArray(); - let heightDimension = new MultiArrayDimension(); - heightDimension.label = 'height'; - heightDimension.size = 480; - heightDimension.stride = 921600; - - let weightDimension = new MultiArrayDimension(); - weightDimension.label = 'weight'; - weightDimension.size = 640; - weightDimension.stride = 1920; - - let channelDimension = new MultiArrayDimension(); - channelDimension.label = 'channel'; - channelDimension.size = 3; - channelDimension.stride = 8; - - float32MultiArray.layout.dim.fill([ - heightDimension, - weightDimension, - channelDimension, - ]); - float32MultiArray.layout.data_offset = 1024; - float32MultiArray.data = [1.0, 2.0, 3.0, 8.5, 6.75, 0.5, -0.25]; - - let float32MultiArrayClone = new Float32MultiArray(float32MultiArray); - assert.deepStrictEqual( - 'height', - float32MultiArrayClone.layout.dim.data[0].label - ); - assert.deepStrictEqual(480, float32MultiArrayClone.layout.dim.data[0].size); - assert.deepStrictEqual( - 921600, - float32MultiArrayClone.layout.dim.data[0].stride - ); - assert.deepStrictEqual( - 'weight', - float32MultiArrayClone.layout.dim.data[1].label - ); - assert.deepStrictEqual(640, float32MultiArrayClone.layout.dim.data[1].size); - assert.deepStrictEqual( - 1920, - float32MultiArrayClone.layout.dim.data[1].stride - ); - assert.deepStrictEqual( - 'channel', - float32MultiArrayClone.layout.dim.data[2].label - ); - assert.deepStrictEqual(3, float32MultiArrayClone.layout.dim.data[2].size); - assert.deepStrictEqual(8, float32MultiArrayClone.layout.dim.data[2].stride); - assert.deepStrictEqual(1024, float32MultiArrayClone.layout.data_offset); - assert.deepStrictEqual( - Float32Array.from([1.0, 2.0, 3.0, 8.5, 6.75, 0.5, -0.25]), - float32MultiArrayClone.data - ); - }); + // not sure how this test works, `Float32MultiArray.layout.dim.data` is not a valid + // field, `MultiArrayDimensions` does not have a `data` field. + if (!useRosIdl) { + it('std_msgs/msg/Float32MultiArray checking', function () { + const Float32MultiArray = rclnodejs.require( + 'std_msgs/msg/Float32MultiArray' + ); + const MultiArrayDimension = rclnodejs.require( + 'std_msgs/msg/MultiArrayDimension' + ); + + let float32MultiArray = new Float32MultiArray(); + let heightDimension = new MultiArrayDimension(); + heightDimension.label = 'height'; + heightDimension.size = 480; + heightDimension.stride = 921600; + + let weightDimension = new MultiArrayDimension(); + weightDimension.label = 'weight'; + weightDimension.size = 640; + weightDimension.stride = 1920; + + let channelDimension = new MultiArrayDimension(); + channelDimension.label = 'channel'; + channelDimension.size = 3; + channelDimension.stride = 8; + + float32MultiArray.layout.dim.fill([ + heightDimension, + weightDimension, + channelDimension, + ]); + float32MultiArray.layout.data_offset = 1024; + float32MultiArray.data = [1.0, 2.0, 3.0, 8.5, 6.75, 0.5, -0.25]; + + let float32MultiArrayClone = new Float32MultiArray(float32MultiArray); + assert.deepStrictEqual( + 'height', + float32MultiArrayClone.layout.dim.data[0].label + ); + assert.deepStrictEqual( + 480, + float32MultiArrayClone.layout.dim.data[0].size + ); + assert.deepStrictEqual( + 921600, + float32MultiArrayClone.layout.dim.data[0].stride + ); + assert.deepStrictEqual( + 'weight', + float32MultiArrayClone.layout.dim.data[1].label + ); + assert.deepStrictEqual( + 640, + float32MultiArrayClone.layout.dim.data[1].size + ); + assert.deepStrictEqual( + 1920, + float32MultiArrayClone.layout.dim.data[1].stride + ); + assert.deepStrictEqual( + 'channel', + float32MultiArrayClone.layout.dim.data[2].label + ); + assert.deepStrictEqual(3, float32MultiArrayClone.layout.dim.data[2].size); + assert.deepStrictEqual( + 8, + float32MultiArrayClone.layout.dim.data[2].stride + ); + assert.deepStrictEqual(1024, float32MultiArrayClone.layout.data_offset); + assert.deepStrictEqual( + Float32Array.from([1.0, 2.0, 3.0, 8.5, 6.75, 0.5, -0.25]), + float32MultiArrayClone.data + ); + }); + } }); diff --git a/test/test-primitive-msg-type-check.js b/test/test-primitive-msg-type-check.js index ea112f24..3d4162ea 100644 --- a/test/test-primitive-msg-type-check.js +++ b/test/test-primitive-msg-type-check.js @@ -17,322 +17,327 @@ const assert = require('assert'); const rclnodejs = require('../index.js'); const assertThrowsError = require('./utils.js').assertThrowsError; - -describe('Rclnodejs message type data testing', function () { - this.timeout(60 * 1000); - - before(function () { - return rclnodejs.init(); - }); - - after(function () { - rclnodejs.shutdown(); - }); - - it('Bool data checking', function () { - var node = rclnodejs.createNode('bool'); - var msgBool = rclnodejs.require('std_msgs').msg.Bool; - var msg = new msgBool(); - - msg.data = true; - assert.ok(msg.data); - - msg.data = false; - assert.ok(!msg.data); - - msg.data = 1; - assert.ok(msg.data); - - msg.data = 0; - assert.ok(!msg.data); - - msg.data = 'ABc'; - assert.ok(msg.data); - - msg.data = ''; - assert.ok(!msg.data); - }); - - it('Char data checking', function () { - var node = rclnodejs.createNode('char'); - var msgChar = rclnodejs.require('std_msgs').msg.Char; - var msg = new msgChar(); - - msg.data = 'A'; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 65); - - assertThrowsError( - () => { - msg.data = -129; - }, - [TypeError, RangeError], - 'out of bounds', - 'Char should be in [-128, 127]' - ); - assertThrowsError( - () => { - msg.data = 128; - }, - [TypeError, RangeError], - 'out of bounds', - 'Char should be in [-128, 127]' - ); - }); - - it('Byte data checking', function () { - var node = rclnodejs.createNode('byte'); - var msgByte = rclnodejs.require('std_msgs').msg.Byte; - var msg = new msgByte(); - - msg.data = 0xa; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 10); - - assertThrowsError( - () => { - msg.data = -1; - }, - [TypeError, RangeError], - 'out of bounds', - 'Byte should be in [0, 255]' - ); - assertThrowsError( - () => { - msg.data = 256; - }, - [TypeError, RangeError], - 'out of bounds', - 'Byte should be in [0, 255]' - ); - }); - - it('String data checking', function () { - var node = rclnodejs.createNode('string'); - var msgString = rclnodejs.require('std_msgs').msg.String; - var msg = new msgString(); - - msg.data = 'rclnodejs'; - assert.deepStrictEqual(typeof msg.data, 'string'); - assert.deepStrictEqual(msg.data, 'rclnodejs'); - - assertThrowsError( - () => { - msg.data = 1; - }, - [TypeError, RangeError], - 'Number/String 64-bit value required', - 'String data is not a string' - ); - assertThrowsError( - () => { - msg.data = 3.14; - }, - [TypeError, RangeError], - 'Number/String 64-bit value required', - 'String data is not a string' - ); - }); - - it('Int8 data checking', function () { - var node = rclnodejs.createNode('int8'); - var msgInt8 = rclnodejs.require('std_msgs').msg.Int8; - var msg = new msgInt8(); - - msg.data = 0x7f; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 127); - - assertThrowsError( - () => { - msg.data = -129; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int8 should be in [-128, 127]' - ); - assertThrowsError( - () => { - msg.data = 128; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int8 should be in [-128, 127]' - ); - }); - - it('UInt8 data checking', function () { - var node = rclnodejs.createNode('uint8'); - var msgUInt8 = rclnodejs.require('std_msgs').msg.UInt8; - var msg = new msgUInt8(); - - msg.data = 0xff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 255); - - assertThrowsError( - () => { - msg.data = -1; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt8 should be in [0, 256]' - ); - assertThrowsError( - () => { - msg.data = 256; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt8 should be in [0, 256]' - ); - }); - - it('Int16 data checking', function () { - var node = rclnodejs.createNode('int16'); - var msgInt16 = rclnodejs.require('std_msgs').msg.Int16; - var msg = new msgInt16(); - - msg.data = 0x7fff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 0x7fff); - - assertThrowsError( - () => { - msg.data = -0x7fff - 2; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int16 should be in [-0x7fff, 0x7fff]' - ); - assertThrowsError( - () => { - msg.data = 0x7ffff + 1; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int16 should be in [-0x7fff, 0x7fff]' - ); - }); - - it('UInt16 data checking', function () { - var node = rclnodejs.createNode('uint16'); - var msgUInt16 = rclnodejs.require('std_msgs').msg.UInt16; - var msg = new msgUInt16(); - - msg.data = 0xffff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 0xffff); - - assertThrowsError( - () => { - msg.data = -1; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt16 should be in [0, 0xffff]' - ); - assertThrowsError( - () => { - msg.data = 0xffff + 1; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt16 should be in [0, 0xffff]' - ); - }); - - it('Int32 data checking', function () { - var node = rclnodejs.createNode('int32'); - var msgInt32 = rclnodejs.require('std_msgs').msg.Int32; - var msg = new msgInt32(); - - msg.data = 0x7fffffff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 0x7fffffff); - - assertThrowsError( - () => { - msg.data = -0x7fffffff - 2; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int32 should be in [-0x7fffffff - 1, 0x7fffffff]' - ); - assertThrowsError( - () => { - msg.data = 0x7ffffffff + 1; - }, - [TypeError, RangeError], - 'out of bounds', - 'Int32 should be in [-0x7fffffff - 1, 0x7fffffff]' - ); - }); - - it('UInt32 data checking', function () { - var node = rclnodejs.createNode('uint32'); - var msgUInt32 = rclnodejs.require('std_msgs').msg.UInt32; - var msg = new msgUInt32(); - - msg.data = 0xffffffff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, 0xffffffff); - - assertThrowsError( - () => { - msg.data = -1; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt32 should be in [0, 0xffffffff]' - ); - assertThrowsError( - () => { - msg.data = 0xffffffff + 1; - }, - [TypeError, RangeError], - 'out of bounds', - 'UInt32 should be in [0, 0xffffffff]' - ); - }); - - it('Int64 data checking', function () { - var node = rclnodejs.createNode('int64'); - var msgInt64 = rclnodejs.require('std_msgs').msg.Int64; - var msg = new msgInt64(); - - msg.data = 0x1fffffffffffff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, Number.MAX_SAFE_INTEGER); - }); - - it('UInt64 data checking', function () { - var node = rclnodejs.createNode('uint64'); - var msgUInt64 = rclnodejs.require('std_msgs').msg.UInt64; - var msg = new msgUInt64(); - - msg.data = 0x1fffffffffffff; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.deepStrictEqual(msg.data, Number.MAX_SAFE_INTEGER); - }); - - it('Float32 data checking', function () { - var node = rclnodejs.createNode('float32'); - var msgFloat32 = rclnodejs.require('std_msgs').msg.Float32; - var msg = new msgFloat32(); - - msg.data = 3.14; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.ok(Math.abs(msg.data - 3.14) < 0.000001); - }); - - it('Float64 data checking', function () { - var node = rclnodejs.createNode('float64'); - var msgFloat64 = rclnodejs.require('std_msgs').msg.Float64; - var msg = new msgFloat64(); - - msg.data = 3.14; - assert.deepStrictEqual(typeof msg.data, 'number'); - assert.ok(Math.abs(msg.data - 3.14) < 0.000001); +const { useRosIdl } = require('../options'); + +// new bindings does not throw on wrong types, invalid types are automatically +// converted to the "zero" value. +if (!useRosIdl) { + describe('Rclnodejs message type data testing', function () { + this.timeout(60 * 1000); + + before(function () { + return rclnodejs.init(); + }); + + after(function () { + rclnodejs.shutdown(); + }); + + it('Bool data checking', function () { + var node = rclnodejs.createNode('bool'); + var msgBool = rclnodejs.require('std_msgs').msg.Bool; + var msg = new msgBool(); + + msg.data = true; + assert.ok(msg.data); + + msg.data = false; + assert.ok(!msg.data); + + msg.data = 1; + assert.ok(msg.data); + + msg.data = 0; + assert.ok(!msg.data); + + msg.data = 'ABc'; + assert.ok(msg.data); + + msg.data = ''; + assert.ok(!msg.data); + }); + + it('Char data checking', function () { + var node = rclnodejs.createNode('char'); + var msgChar = rclnodejs.require('std_msgs').msg.Char; + var msg = new msgChar(); + + msg.data = 'A'; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 65); + + assertThrowsError( + () => { + msg.data = -129; + }, + [TypeError, RangeError], + 'out of bounds', + 'Char should be in [-128, 127]' + ); + assertThrowsError( + () => { + msg.data = 128; + }, + [TypeError, RangeError], + 'out of bounds', + 'Char should be in [-128, 127]' + ); + }); + + it('Byte data checking', function () { + var node = rclnodejs.createNode('byte'); + var msgByte = rclnodejs.require('std_msgs').msg.Byte; + var msg = new msgByte(); + + msg.data = 0xa; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 10); + + assertThrowsError( + () => { + msg.data = -1; + }, + [TypeError, RangeError], + 'out of bounds', + 'Byte should be in [0, 255]' + ); + assertThrowsError( + () => { + msg.data = 256; + }, + [TypeError, RangeError], + 'out of bounds', + 'Byte should be in [0, 255]' + ); + }); + + it('String data checking', function () { + var node = rclnodejs.createNode('string'); + var msgString = rclnodejs.require('std_msgs').msg.String; + var msg = new msgString(); + + msg.data = 'rclnodejs'; + assert.deepStrictEqual(typeof msg.data, 'string'); + assert.deepStrictEqual(msg.data, 'rclnodejs'); + + assertThrowsError( + () => { + msg.data = 1; + }, + [TypeError, RangeError], + 'Number/String 64-bit value required', + 'String data is not a string' + ); + assertThrowsError( + () => { + msg.data = 3.14; + }, + [TypeError, RangeError], + 'Number/String 64-bit value required', + 'String data is not a string' + ); + }); + + it('Int8 data checking', function () { + var node = rclnodejs.createNode('int8'); + var msgInt8 = rclnodejs.require('std_msgs').msg.Int8; + var msg = new msgInt8(); + + msg.data = 0x7f; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 127); + + assertThrowsError( + () => { + msg.data = -129; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int8 should be in [-128, 127]' + ); + assertThrowsError( + () => { + msg.data = 128; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int8 should be in [-128, 127]' + ); + }); + + it('UInt8 data checking', function () { + var node = rclnodejs.createNode('uint8'); + var msgUInt8 = rclnodejs.require('std_msgs').msg.UInt8; + var msg = new msgUInt8(); + + msg.data = 0xff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 255); + + assertThrowsError( + () => { + msg.data = -1; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt8 should be in [0, 256]' + ); + assertThrowsError( + () => { + msg.data = 256; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt8 should be in [0, 256]' + ); + }); + + it('Int16 data checking', function () { + var node = rclnodejs.createNode('int16'); + var msgInt16 = rclnodejs.require('std_msgs').msg.Int16; + var msg = new msgInt16(); + + msg.data = 0x7fff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 0x7fff); + + assertThrowsError( + () => { + msg.data = -0x7fff - 2; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int16 should be in [-0x7fff, 0x7fff]' + ); + assertThrowsError( + () => { + msg.data = 0x7ffff + 1; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int16 should be in [-0x7fff, 0x7fff]' + ); + }); + + it('UInt16 data checking', function () { + var node = rclnodejs.createNode('uint16'); + var msgUInt16 = rclnodejs.require('std_msgs').msg.UInt16; + var msg = new msgUInt16(); + + msg.data = 0xffff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 0xffff); + + assertThrowsError( + () => { + msg.data = -1; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt16 should be in [0, 0xffff]' + ); + assertThrowsError( + () => { + msg.data = 0xffff + 1; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt16 should be in [0, 0xffff]' + ); + }); + + it('Int32 data checking', function () { + var node = rclnodejs.createNode('int32'); + var msgInt32 = rclnodejs.require('std_msgs').msg.Int32; + var msg = new msgInt32(); + + msg.data = 0x7fffffff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 0x7fffffff); + + assertThrowsError( + () => { + msg.data = -0x7fffffff - 2; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int32 should be in [-0x7fffffff - 1, 0x7fffffff]' + ); + assertThrowsError( + () => { + msg.data = 0x7ffffffff + 1; + }, + [TypeError, RangeError], + 'out of bounds', + 'Int32 should be in [-0x7fffffff - 1, 0x7fffffff]' + ); + }); + + it('UInt32 data checking', function () { + var node = rclnodejs.createNode('uint32'); + var msgUInt32 = rclnodejs.require('std_msgs').msg.UInt32; + var msg = new msgUInt32(); + + msg.data = 0xffffffff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, 0xffffffff); + + assertThrowsError( + () => { + msg.data = -1; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt32 should be in [0, 0xffffffff]' + ); + assertThrowsError( + () => { + msg.data = 0xffffffff + 1; + }, + [TypeError, RangeError], + 'out of bounds', + 'UInt32 should be in [0, 0xffffffff]' + ); + }); + + it('Int64 data checking', function () { + var node = rclnodejs.createNode('int64'); + var msgInt64 = rclnodejs.require('std_msgs').msg.Int64; + var msg = new msgInt64(); + + msg.data = 0x1fffffffffffff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, Number.MAX_SAFE_INTEGER); + }); + + it('UInt64 data checking', function () { + var node = rclnodejs.createNode('uint64'); + var msgUInt64 = rclnodejs.require('std_msgs').msg.UInt64; + var msg = new msgUInt64(); + + msg.data = 0x1fffffffffffff; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.deepStrictEqual(msg.data, Number.MAX_SAFE_INTEGER); + }); + + it('Float32 data checking', function () { + var node = rclnodejs.createNode('float32'); + var msgFloat32 = rclnodejs.require('std_msgs').msg.Float32; + var msg = new msgFloat32(); + + msg.data = 3.14; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.ok(Math.abs(msg.data - 3.14) < 0.000001); + }); + + it('Float64 data checking', function () { + var node = rclnodejs.createNode('float64'); + var msgFloat64 = rclnodejs.require('std_msgs').msg.Float64; + var msg = new msgFloat64(); + + msg.data = 3.14; + assert.deepStrictEqual(typeof msg.data, 'number'); + assert.ok(Math.abs(msg.data - 3.14) < 0.000001); + }); }); -}); +} diff --git a/test/test-rosidl-message-generator.js b/test/test-rosidl-message-generator.js index 6048dc3b..58667f7d 100644 --- a/test/test-rosidl-message-generator.js +++ b/test/test-rosidl-message-generator.js @@ -17,6 +17,7 @@ const assert = require('assert'); const os = require('os'); const rclnodejs = require('../index.js'); +const { useRosIdl } = require('../options'); describe('ROSIDL Node.js message generator test suite', function () { before(function () { @@ -38,6 +39,10 @@ describe('ROSIDL Node.js message generator test suite', function () { let promises = []; installedPackagesRoot.forEach((path) => { let promise = packages.findPackagesInDirectory(path).then((pkgs) => { + if (useRosIdl) { + // this packages contains invalid messages + pkgs.delete('libstatistics_collector'); + } pkgs.forEach((pkg) => { pkg.messages.forEach((info) => { const s = @@ -127,8 +132,12 @@ describe('ROSIDL Node.js message generator test suite', function () { let Point = rclnodejs.require('geometry_msgs').msg.Point; let Quaternion = rclnodejs.require('geometry_msgs').msg.Quaternion; let msg = new Pose(); - assert(msg.position instanceof Point); - assert(msg.orientation instanceof Quaternion); + + // new bindings doesn't initialize nested messages with wrappers. + if (!useRosIdl) { + assert(msg.position instanceof Point); + assert(msg.orientation instanceof Quaternion); + } // Setter + getter msg.position.x = 123.5; @@ -182,42 +191,45 @@ describe('ROSIDL Node.js message generator test suite', function () { assert.equal(copy.position.z, 78901.125); }); - it('Testing array - Int32', function () { - let Int32 = rclnodejs.require('std_msgs').msg.Int32; - let array = new Int32.ArrayType(5); - - assert(array.data instanceof Int32Array); - assert(typeof array.data[5] === 'undefined'); // No such index - assert.equal(array.size, 5); - assert.equal(array.capacity, 5); - - // Assignment of message.data - const int32Data = [153, 26, 777, 666, 999]; - for (let i = 0; i < int32Data.length; ++i) { - array.data[i] = int32Data[i]; - assert.equal(array.data[i], int32Data[i]); // Verifying - } - - // Array deep copy - let array2 = new Int32.ArrayType(); - array2.copy(array); - for (let i = 0; i < int32Data.length; ++i) { - assert.equal(array2.data[i], int32Data[i]); - } - - // Change array2 - for (let i = 0; i < array2.length; ++i) { - array2.data[i] = 0; - } - - // Values in array1 are NOT changed - for (let i = 0; i < array.length; ++i) { - assert.equal(array.data[i], int32Data[i]); // Verifying - } - - // Resize - array.size = 6; - assert.equal(array.size, 6); - assert.equal(array.capacity, 6); - }); + // new bindings does not have array wrappers. + if (!useRosIdl) { + it('Testing array - Int32', function () { + let Int32 = rclnodejs.require('std_msgs').msg.Int32; + let array = new Int32.ArrayType(5); + + assert(array.data instanceof Int32Array); + assert(typeof array.data[5] === 'undefined'); // No such index + assert.equal(array.size, 5); + assert.equal(array.capacity, 5); + + // Assignment of message.data + const int32Data = [153, 26, 777, 666, 999]; + for (let i = 0; i < int32Data.length; ++i) { + array.data[i] = int32Data[i]; + assert.equal(array.data[i], int32Data[i]); // Verifying + } + + // Array deep copy + let array2 = new Int32.ArrayType(); + array2.copy(array); + for (let i = 0; i < int32Data.length; ++i) { + assert.equal(array2.data[i], int32Data[i]); + } + + // Change array2 + for (let i = 0; i < array2.length; ++i) { + array2.data[i] = 0; + } + + // Values in array1 are NOT changed + for (let i = 0; i < array.length; ++i) { + assert.equal(array.data[i], int32Data[i]); // Verifying + } + + // Resize + array.size = 6; + assert.equal(array.size, 6); + assert.equal(array.capacity, 6); + }); + } }); diff --git a/test/test-security-related.js b/test/test-security-related.js index b24bf4f1..418fabc6 100644 --- a/test/test-security-related.js +++ b/test/test-security-related.js @@ -19,6 +19,7 @@ const rclnodejs = require('../index.js'); const assertThrowsError = require('./utils.js').assertThrowsError; const translator = require('../rosidl_gen/message_translator.js'); const arrayGen = require('./array_generator.js'); +const { useRosIdl } = require('../options'); describe('Destroying non-existent objects testing', function () { this.timeout(60 * 1000); @@ -213,54 +214,62 @@ describe('Fuzzing API calls testing', function () { node.destroy(); }); - it('Inconsistent message type for subscription', function () { - var node = rclnodejs.createNode('node1', '/inconsistent'); - const RclString = 'std_msgs/msg/String'; - - var publisher = node.createPublisher(RclString, 'chatter7'); - assertThrowsError( - () => { - publisher.publish({ a: 1 }); - }, - TypeError, - 'Invalid argument', - `Type should be ${RclString}` - ); - - rclnodejs.spin(node); - node.destroy(); - }); + // new bindings does not throw on wrong types, invalid values are defaulted to their + // "zero" value. + if (!useRosIdl) { + it('Inconsistent message type for subscription', function () { + var node = rclnodejs.createNode('node1', '/inconsistent'); + const RclString = 'std_msgs/msg/String'; - it('Inconsistent request data for service', function () { - var node = rclnodejs.createNode('node2', '/inconsistent'); - const AddTwoInts = 'example_interfaces/srv/AddTwoInts'; + var publisher = node.createPublisher(RclString, 'chatter7'); + assertThrowsError( + () => { + publisher.publish({ a: 1 }); + }, + TypeError, + 'Invalid argument', + `Type should be ${RclString}` + ); - var client = node.createClient(AddTwoInts, 'add_two_ints'); - var service = node.createService( - AddTwoInts, - 'add_two_ints', - (request, response) => { - assert.throws( - () => { - request.b; - }, - Error, - 'This should never be reached.' - ); - } - ); + rclnodejs.spin(node); + node.destroy(); + }); + } + + // new bindings does not throw on wrong types, invalid values are defaulted to their + // "zero" value. + if (!useRosIdl) { + it('Inconsistent request data for service', function () { + var node = rclnodejs.createNode('node2', '/inconsistent'); + const AddTwoInts = 'example_interfaces/srv/AddTwoInts'; + + var client = node.createClient(AddTwoInts, 'add_two_ints'); + var service = node.createService( + AddTwoInts, + 'add_two_ints', + (request, response) => { + assert.throws( + () => { + request.b; + }, + Error, + 'This should never be reached.' + ); + } + ); - assertThrowsError( - () => { - client.sendRequest({ a: 1 }, (response) => {}); - }, - TypeError, - 'Invalid argument', - 'request.b does not exist' - ); - rclnodejs.spin(node); - node.destroy(); - }); + assertThrowsError( + () => { + client.sendRequest({ a: 1 }, (response) => {}); + }, + TypeError, + 'Invalid argument', + 'request.b does not exist' + ); + rclnodejs.spin(node); + node.destroy(); + }); + } it('resources will be freed by shutdown', function () { var node = rclnodejs.createNode('node1', '/unhandled'); diff --git a/test/test-single-process.js b/test/test-single-process.js index 75b871f9..df5d4ca5 100644 --- a/test/test-single-process.js +++ b/test/test-single-process.js @@ -16,6 +16,7 @@ const assert = require('assert'); const rclnodejs = require('../index.js'); +const { useRosIdl } = require('../options'); describe('Test rclnodejs nodes in a single process', function () { this.timeout(60 * 1000); @@ -51,7 +52,11 @@ describe('Test rclnodejs nodes in a single process', function () { 'single_ps_channel1' ); var timer = publisherNode.createTimer(100, () => { - publisher.publish(msg); + if (useRosIdl) { + publisher.publish({ data: msg }); // short form not supported by rosidl generator + } else { + publisher.publish(msg); + } }); rclnodejs.spin(subscriptionNode); rclnodejs.spin(publisherNode);