diff --git a/examples/node_simple.js b/examples/node_simple.js index 5829fa46d..e4144eda2 100644 --- a/examples/node_simple.js +++ b/examples/node_simple.js @@ -28,7 +28,7 @@ var cmdVel = new ROSLIB.Topic({ messageType: 'geometry_msgs/Twist' }); -var twist = new ROSLIB.Message({ +var twist = { linear: { x: 0.1, y: 0.2, @@ -39,7 +39,7 @@ angular: { y: -0.2, z: -0.3 } -}); +}; console.log('Publishing cmd_vel'); cmdVel.publish(twist); diff --git a/examples/react-example/src/component_examples/example_functions.jsx b/examples/react-example/src/component_examples/example_functions.jsx index 0ab415678..4b9d4cade 100644 --- a/examples/react-example/src/component_examples/example_functions.jsx +++ b/examples/react-example/src/component_examples/example_functions.jsx @@ -46,11 +46,11 @@ function SendMessage() { messageType: 'geometry_msgs/Pose2D' }) - const data = new ROSLIB.Message({ - x: linear.x, - y: linear.y, - theta: angular.z - }) + const data = { + x: linear.x, + y: linear.y, + theta: angular.z + } // publishes to the queue console.log('msg', data) diff --git a/examples/ros2_simple.html b/examples/ros2_simple.html index 4d61b99a9..927d46901 100644 --- a/examples/ros2_simple.html +++ b/examples/ros2_simple.html @@ -49,7 +49,7 @@ // Then we create the payload to be published. The object we pass in to ros.Message matches the // fields defined in the geometry_msgs/Twist.msg definition. - var twist = new ROSLIB.Message({ + var twist = { linear : { x : 0.1, y : 0.2, @@ -60,7 +60,7 @@ y : -0.2, z : -0.3 } - }); + }; // And finally, publish. cmdVel.publish(twist); @@ -96,10 +96,10 @@ // Then we create a Service Request. The object we pass in to ROSLIB.ServiceRequest matches the // fields defined in the rospy_tutorials AddTwoInts.srv file. - var request = new ROSLIB.ServiceRequest({ + var request = { a : 1, b : 2 - }); + }; // Finally, we call the /add_two_ints service and get back the results in the callback. The result // is a ROSLIB.ServiceResponse object. diff --git a/examples/simple.html b/examples/simple.html index 00661209b..93b193dcf 100644 --- a/examples/simple.html +++ b/examples/simple.html @@ -49,7 +49,7 @@ // Then we create the payload to be published. The object we pass in to ros.Message matches the // fields defined in the geometry_msgs/Twist.msg definition. - var twist = new ROSLIB.Message({ + var twist = { linear : { x : 0.1, y : 0.2, @@ -60,7 +60,7 @@ y : -0.2, z : -0.3 } - }); + }; // And finally, publish. cmdVel.publish(twist); @@ -96,10 +96,10 @@ // Then we create a Service Request. The object we pass in to ROSLIB.ServiceRequest matches the // fields defined in the rospy_tutorials AddTwoInts.srv file. - var request = new ROSLIB.ServiceRequest({ + var request = { a : 1, b : 2 - }); + }; // Finally, we call the /add_two_ints service and get back the results in the callback. The result // is a ROSLIB.ServiceResponse object. diff --git a/src/actionlib/ActionClient.js b/src/actionlib/ActionClient.js index 77ff25c64..7baeb6090 100644 --- a/src/actionlib/ActionClient.js +++ b/src/actionlib/ActionClient.js @@ -128,7 +128,7 @@ export default class ActionClient extends EventEmitter { * Cancel all goals associated with this ActionClient. */ cancel() { - var cancelMessage = new Message(); + var cancelMessage = {}; this.cancelTopic.publish(cancelMessage); } /** diff --git a/src/actionlib/Goal.js b/src/actionlib/Goal.js index cad25f939..b7f0100a4 100644 --- a/src/actionlib/Goal.js +++ b/src/actionlib/Goal.js @@ -35,7 +35,7 @@ export default class Goal extends EventEmitter { // Create a random ID this.goalID = 'goal_' + Math.random() + '_' + date.getTime(); // Fill in the goal message - this.goalMessage = new Message({ + this.goalMessage = { goal_id: { stamp: { secs: 0, @@ -44,7 +44,7 @@ export default class Goal extends EventEmitter { id: this.goalID }, goal: this.goalMessage - }); + }; this.on('status', function (status) { that.status = status; @@ -82,9 +82,9 @@ export default class Goal extends EventEmitter { * Cancel the current goal. */ cancel() { - var cancelMessage = new Message({ + var cancelMessage = { id: this.goalID - }); + }; this.actionClient.cancelTopic.publish(cancelMessage); } } diff --git a/src/actionlib/SimpleActionServer.js b/src/actionlib/SimpleActionServer.js index 768032bef..3816cf0d6 100644 --- a/src/actionlib/SimpleActionServer.js +++ b/src/actionlib/SimpleActionServer.js @@ -4,7 +4,6 @@ */ import Topic from '../core/Topic.js'; -import Message from '../core/Message.js'; import Ros from '../core/Ros.js'; import { EventEmitter } from 'eventemitter3'; @@ -65,13 +64,14 @@ export default class SimpleActionServer extends EventEmitter { }); // Track the goals and their status in order to publish status... - this.statusMessage = new Message({ + this.statusMessage = { header: { stamp: { secs: 0, nsecs: 100 }, frame_id: '' }, + /** @type {{goal_id: any, status: number}[]} */ status_list: [] - }); + }; // needed for handling preemption prompted by a new goal being received this.currentGoal = null; // currently tracked goal @@ -83,10 +83,7 @@ export default class SimpleActionServer extends EventEmitter { // needs to happen AFTER rest is set up that.emit('cancel'); } else { - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. - that.statusMessage.status_list = [ - { goal_id: goalMessage.goal_id, status: 1 } - ]; + that.statusMessage.status_list = [{ goal_id: goalMessage.goal_id, status: 1 }]; that.currentGoal = goalMessage; that.emit('goal', goalMessage.goal); } @@ -157,9 +154,7 @@ export default class SimpleActionServer extends EventEmitter { var nsecs = Math.round( 1000000000 * (currentTime.getTime() / 1000 - secs) ); - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. that.statusMessage.header.stamp.secs = secs; - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. that.statusMessage.header.stamp.nsecs = nsecs; statusPublisher.publish(that.statusMessage); }, 500); // publish every 500ms @@ -170,13 +165,12 @@ export default class SimpleActionServer extends EventEmitter { * @param {Object} result - The result to return to the client. */ setSucceeded(result) { - var resultMessage = new Message({ + var resultMessage = { status: { goal_id: this.currentGoal.goal_id, status: 3 }, result: result - }); + }; this.resultPublisher.publish(resultMessage); - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. this.statusMessage.status_list = []; if (this.nextGoal) { this.currentGoal = this.nextGoal; @@ -192,13 +186,12 @@ export default class SimpleActionServer extends EventEmitter { * @param {Object} result - The result to return to the client. */ setAborted(result) { - var resultMessage = new Message({ + var resultMessage = { status: { goal_id: this.currentGoal.goal_id, status: 4 }, result: result - }); + }; this.resultPublisher.publish(resultMessage); - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. this.statusMessage.status_list = []; if (this.nextGoal) { this.currentGoal = this.nextGoal; @@ -214,21 +207,20 @@ export default class SimpleActionServer extends EventEmitter { * @param {Object} feedback - The feedback to send to the client. */ sendFeedback(feedback) { - var feedbackMessage = new Message({ + var feedbackMessage = { status: { goal_id: this.currentGoal.goal_id, status: 1 }, feedback: feedback - }); + }; this.feedbackPublisher.publish(feedbackMessage); } /** * Handle case where client requests preemption. */ setPreempted() { - // @ts-expect-error -- we need to design a way to handle arbitrary fields in Message types. this.statusMessage.status_list = []; - var resultMessage = new Message({ + var resultMessage = { status: { goal_id: this.currentGoal.goal_id, status: 2 } - }); + }; this.resultPublisher.publish(resultMessage); if (this.nextGoal) { diff --git a/src/core/Param.js b/src/core/Param.js index ccc534358..cbaad60c7 100644 --- a/src/core/Param.js +++ b/src/core/Param.js @@ -4,7 +4,6 @@ */ import Service from './Service.js'; -import ServiceRequest from './ServiceRequest.js'; import Ros from '../core/Ros.js'; /** @@ -41,9 +40,7 @@ export default class Param { serviceType: 'rosapi/GetParam' }); - var request = new ServiceRequest({ - name: this.name - }); + var request = {name: this.name}; paramClient.callService( request, @@ -76,10 +73,10 @@ export default class Param { serviceType: 'rosapi/SetParam' }); - var request = new ServiceRequest({ + var request = { name: this.name, value: JSON.stringify(value) - }); + }; paramClient.callService(request, callback, failedCallback); } @@ -96,9 +93,9 @@ export default class Param { serviceType: 'rosapi/DeleteParam' }); - var request = new ServiceRequest({ + var request = { name: this.name - }); + }; paramClient.callService(request, callback, failedCallback); } diff --git a/src/core/Ros.js b/src/core/Ros.js index 913ddb49e..b834a9b81 100644 --- a/src/core/Ros.js +++ b/src/core/Ros.js @@ -5,12 +5,9 @@ import socketAdapter from './SocketAdapter.js'; -import Service from './Service.js'; -import ServiceRequest from './ServiceRequest.js'; -import ServiceResponse from './ServiceResponse.js'; - import assign from 'object-assign'; import Topic from './Topic.js'; +import Service from './Service.js'; import Param from './Param.js'; import TFClient from '../tf/TFClient.js'; import ActionClient from '../actionlib/ActionClient.js'; @@ -181,7 +178,7 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/GetActionServers' }); - var request = new ServiceRequest({}); + var request = {}; if (typeof failedCallback === 'function') { getActionServers.callService( request, @@ -221,7 +218,7 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/Topics' }); - var request = new ServiceRequest(); + var request = {}; if (typeof failedCallback === 'function') { topicsClient.callService( request, @@ -260,9 +257,9 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/TopicsForType' }); - var request = new ServiceRequest({ + var request = { type: topicType - }); + }; if (typeof failedCallback === 'function') { topicsForTypeClient.callService( request, @@ -300,7 +297,7 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/Services' }); - var request = new ServiceRequest(); + var request = {}; if (typeof failedCallback === 'function') { servicesClient.callService( request, @@ -339,9 +336,9 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/ServicesForType' }); - var request = new ServiceRequest({ + var request = { type: serviceType - }); + }; if (typeof failedCallback === 'function') { servicesForTypeClient.callService( request, @@ -380,9 +377,9 @@ export default class Ros extends EventEmitter { name: '/rosapi/service_request_details', serviceType: 'rosapi/ServiceRequestDetails' }); - var request = new ServiceRequest({ + var request = { type: type - }); + }; if (typeof failedCallback === 'function') { serviceTypeClient.callService( @@ -402,7 +399,7 @@ export default class Ros extends EventEmitter { } /** * @callback getServiceResponseDetailsCallback - * @param {ServiceResponse<{typedefs: string[]}>} result - The result object with the following params: + * @param {{typedefs: string[]}} result - The result object with the following params: */ /** * @callback getServiceResponseDetailsFailedCallback @@ -422,9 +419,9 @@ export default class Ros extends EventEmitter { name: '/rosapi/service_response_details', serviceType: 'rosapi/ServiceResponseDetails' }); - var request = new ServiceRequest({ + var request = { type: type - }); + }; if (typeof failedCallback === 'function') { serviceTypeClient.callService( @@ -463,7 +460,7 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/Nodes' }); - var request = new ServiceRequest(); + var request = {}; if (typeof failedCallback === 'function') { nodesClient.callService( request, @@ -523,9 +520,9 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/NodeDetails' }); - var request = new ServiceRequest({ + var request = { node: node - }); + }; if (typeof failedCallback === 'function') { nodesClient.callService( request, @@ -563,7 +560,7 @@ export default class Ros extends EventEmitter { name: '/rosapi/get_param_names', serviceType: 'rosapi/GetParamNames' }); - var request = new ServiceRequest(); + var request = {}; if (typeof failedCallback === 'function') { paramsClient.callService( request, @@ -601,9 +598,9 @@ export default class Ros extends EventEmitter { name: '/rosapi/topic_type', serviceType: 'rosapi/TopicType' }); - var request = new ServiceRequest({ + var request = { topic: topic - }); + }; if (typeof failedCallback === 'function') { topicTypeClient.callService( @@ -642,9 +639,9 @@ export default class Ros extends EventEmitter { name: '/rosapi/service_type', serviceType: 'rosapi/ServiceType' }); - var request = new ServiceRequest({ + var request = { service: service - }); + }; if (typeof failedCallback === 'function') { serviceTypeClient.callService( @@ -683,9 +680,9 @@ export default class Ros extends EventEmitter { name: '/rosapi/message_details', serviceType: 'rosapi/MessageDetails' }); - var request = new ServiceRequest({ + var request = { type: message - }); + }; if (typeof failedCallback === 'function') { messageDetailClient.callService( @@ -778,7 +775,7 @@ export default class Ros extends EventEmitter { serviceType: 'rosapi/TopicsAndRawTypes' }); - var request = new ServiceRequest(); + var request = {}; if (typeof failedCallback === 'function') { topicsAndRawTypesClient.callService( request, diff --git a/src/core/Service.js b/src/core/Service.js index 131d91a2f..6ebc52179 100644 --- a/src/core/Service.js +++ b/src/core/Service.js @@ -3,8 +3,6 @@ * @author Brandon Alexander - baalexander@gmail.com */ -import ServiceResponse from './ServiceResponse.js'; -import ServiceRequest from './ServiceRequest.js'; import Ros from './Ros.js'; import { EventEmitter } from 'eventemitter3'; @@ -40,7 +38,7 @@ export default class Service extends EventEmitter { * Call the service. Returns the service response in the * callback. Does nothing if this service is currently advertised. * - * @param {TRequest} request - The ROSLIB.ServiceRequest to send. + * @param {TRequest} request - The service request to send. * @param {callServiceCallback} [callback] - Function with the following params: * @param {callServiceFailedCallback} [failedCallback] - The callback function when the service call failed with params: */ @@ -59,8 +57,7 @@ export default class Service extends EventEmitter { failedCallback(message.values); } } else if (typeof callback === 'function') { - // @ts-expect-error -- can't figure out how to get ServiceResponse to play nice in typescript here - callback(new ServiceResponse(message.values)); + callback(message.values); } }); } @@ -76,7 +73,7 @@ export default class Service extends EventEmitter { } /** * @callback advertiseCallback - * @param {ServiceRequest} request - The service request. + * @param {TRequest} request - The service request. * @param {Object} response - An empty dictionary. Take care not to overwrite this. Instead, only modify the values within. * It should return true if the service has finished successfully, * i.e., without any fatal errors. @@ -120,7 +117,7 @@ export default class Service extends EventEmitter { var call = { op: 'service_response', service: this.name, - values: new ServiceResponse(response), + values: response, result: success }; diff --git a/src/core/ServiceRequest.js b/src/core/ServiceRequest.js deleted file mode 100644 index 55840817d..000000000 --- a/src/core/ServiceRequest.js +++ /dev/null @@ -1,21 +0,0 @@ -/** - * @fileOverview - * @author Brandon Alexander - balexander@willowgarage.com - */ - -import assign from 'object-assign'; - -/** - * A ServiceRequest is passed into the service call. - * - * @constructor - * @template T -*/ -export default class ServiceRequest { - /** - * @param {T} [values={}] - Object matching the fields defined in the .srv definition file. - */ - constructor(values) { - assign(this, values || {}); - } -} diff --git a/src/core/ServiceResponse.js b/src/core/ServiceResponse.js deleted file mode 100644 index 210731085..000000000 --- a/src/core/ServiceResponse.js +++ /dev/null @@ -1,21 +0,0 @@ -/** - * @fileOverview - * @author Brandon Alexander - balexander@willowgarage.com - */ - -import assign from 'object-assign'; - -/** - * A ServiceResponse is returned from the service call. - * - * @constructor - * @template T -*/ -export default class ServiceResponse { - /** - * @param {T} values - Object matching the fields defined in the .srv definition file. - */ - constructor(values) { - assign(this, values); - } -} diff --git a/src/core/Topic.js b/src/core/Topic.js index a06463d8e..990d7931b 100644 --- a/src/core/Topic.js +++ b/src/core/Topic.js @@ -4,7 +4,6 @@ */ import { EventEmitter } from 'eventemitter3'; -import Message from './Message.js'; import Ros from './Ros.js'; /** @@ -90,7 +89,7 @@ export default class Topic extends EventEmitter { } this._messageCallback = function (data) { - that.emit('message', new Message(data)); + that.emit('message', data); }; } /** @@ -205,7 +204,7 @@ export default class Topic extends EventEmitter { /** * Publish the message. * - * @param {T} message - A ROSLIB.Message object. + * @param {T} message - The message to publish. */ publish(message) { if (!this.isAdvertised) { diff --git a/src/core/index.js b/src/core/index.js index 4b6f362e5..5745e0ebc 100644 --- a/src/core/index.js +++ b/src/core/index.js @@ -1,8 +1,5 @@ export {default as Ros} from './Ros.js'; export {default as Topic} from './Topic.js'; -export {default as Message} from './Message.js'; export {default as Param} from './Param.js'; export {default as Service} from './Service.js'; -export {default as ServiceRequest} from './ServiceRequest.js'; -export {default as ServiceResponse} from './ServiceResponse.js'; export {default as Action} from './Action.js'; diff --git a/src/tf/TFClient.js b/src/tf/TFClient.js index 47cd7f798..b4d9e61e9 100644 --- a/src/tf/TFClient.js +++ b/src/tf/TFClient.js @@ -7,7 +7,6 @@ import ActionClient from '../actionlib/ActionClient.js'; import Goal from '../actionlib/Goal.js'; import Service from '../core/Service.js'; -import ServiceRequest from '../core/ServiceRequest.js'; import Topic from '../core/Topic.js'; import Transform from '../math/Transform.js'; @@ -131,9 +130,7 @@ export default class TFClient extends EventEmitter { // The service interface has the same parameters as the action, // plus the timeout goalMessage.timeout = this.topicTimeout; - var request = new ServiceRequest(goalMessage); - - this.serviceClient.callService(request, this.processResponse.bind(this)); + this.serviceClient.callService(goalMessage, this.processResponse.bind(this)); } this.republisherUpdateRequested = false; diff --git a/test/examples/topic-listener.example.js b/test/examples/topic-listener.example.js index aa8be9c4a..8470c8f56 100644 --- a/test/examples/topic-listener.example.js +++ b/test/examples/topic-listener.example.js @@ -41,7 +41,6 @@ describe('Topics Example', function() { var expected = messages.slice(); topic.subscribe(function(message) { - expect(message).to.be.instanceof(ROSLIB.Message); expect(message).to.be.eql(expected.shift()); });