Skip to content

Commit a2ffcad

Browse files
committed
Generating message handlers from .msg files
1 parent 4c604d3 commit a2ffcad

10 files changed

Lines changed: 1084 additions & 91 deletions

File tree

example.js

Lines changed: 75 additions & 60 deletions
Original file line numberDiff line numberDiff line change
@@ -1,71 +1,86 @@
11
'use strict';
22

33
let rosnodejs = require('./index.js');
4-
const std_msgs = rosnodejs.require('std_msgs').msg;
5-
const SetBool = rosnodejs.require('std_srvs').srv.SetBool;
4+
// const std_msgs = rosnodejs.require('std_msgs').msg;
5+
// const SetBool = rosnodejs.require('std_srvs').srv.SetBool;
66

7-
rosnodejs.initNode('/my_node')
8-
.then((rosNode) => {
9-
// EXP 1) Service Server
10-
let service = rosNode.advertiseService({
11-
service: '/set_bool',
12-
type: 'std_srvs/SetBool'
13-
}, (req, resp) => {
14-
console.log('Handling request! ' + JSON.stringify(req));
15-
resp.success = !req.data;
16-
resp.message = 'Inverted!';
17-
return true;
18-
});
7+
// aspirational:
8+
rosnodejs.use(['std_msgs/String'], function() {
199

20-
// EXP 2) Service Client
21-
let serviceClient = rosNode.serviceClient({
22-
service: '/set_bool',
23-
type: 'std_srvs/SetBool'
24-
});
25-
rosNode.waitForService(serviceClient.getService(), 2000)
26-
.then((available) => {
27-
if (available) {
28-
const request = new SetBool.Request();
29-
request.data = true;
30-
serviceClient.call(request, (resp) => {
31-
console.log('Service response ' + JSON.stringify(resp));
32-
});
33-
}
34-
});
10+
const msg = new (rosnodejs.message('std_msgs/String'))(
11+
{ data: "howdy" });
12+
// console.log(msg,
13+
// Object.getOwnPropertyNames(msg),
14+
// msg.md5,
15+
// msg.__proto__);
16+
17+
18+
rosnodejs.initNode('/my_node')
19+
.then((rosNode) => {
20+
// EXP 1) Service Server
21+
// let service = rosNode.advertiseService({
22+
// service: '/set_bool',
23+
// type: 'std_srvs/SetBool'
24+
// }, (req, resp) => {
25+
// console.log('Handling request! ' + JSON.stringify(req));
26+
// resp.success = !req.data;
27+
// resp.message = 'Inverted!';
28+
// return true;
29+
// });
3530

36-
// EXP 3) Params
37-
rosNode.setParam('~junk', {'hi': 2}).then(() => {
38-
rosNode.getParam('~junk').then((val) => { console.log('Got Param!!! ' + JSON.stringify(val)); });
39-
});
31+
// // EXP 2) Service Client
32+
// let serviceClient = rosNode.serviceClient({
33+
// service: '/set_bool',
34+
// type: 'std_srvs/SetBool'
35+
// });
36+
// rosNode.waitForService(serviceClient.getService(), 2000)
37+
// .then((available) => {
38+
// if (available) {
39+
// const request = new SetBool.Request();
40+
// request.data = true;
41+
// serviceClient.call(request, (resp) => {
42+
// console.log('Service response ' + JSON.stringify(resp));
43+
// });
44+
// }
45+
// });
4046

41-
// EXP 4) Publisher
42-
let pub = rosNode.advertise({
43-
topic: '/my_topic',
44-
type: 'std_msgs/String',
45-
queueSize: 1,
46-
latching: true,
47-
throttleMs: 9
48-
});
47+
// // EXP 3) Params
48+
// rosNode.setParam('~junk', {'hi': 2}).then(() => {
49+
// rosNode.getParam('~junk').then((val) => { console.log('Got Param!!! ' + JSON.stringify(val)); });
50+
// });
4951

50-
let msgStart = 'my message ';
51-
let iter = 0;
52-
const msg = new std_msgs.String();
53-
setInterval(() => {
54-
msg.data = msgStart + iter
55-
pub.publish(msg);
56-
++iter;
57-
if (iter > 200) {
58-
iter = 0;
59-
}
60-
}, 5);
52+
// // EXP 4) Publisher
53+
let pub = rosNode.advertise({
54+
topic: '/my_topic',
55+
type: 'std_msgs/String',
56+
queueSize: 1,
57+
latching: true,
58+
throttleMs: 9
59+
});
60+
61+
let msgStart = 'my message ';
62+
let iter = 0;
63+
// const msg = new std_msgs.String(); // already created above
64+
setInterval(() => {
65+
// console.log(".");
66+
msg.data = msgStart + iter
67+
pub.publish(msg);
68+
++iter;
69+
if (iter > 200) {
70+
iter = 0;
71+
}
72+
}, 5);
6173

62-
// EXP 5) Subscriber
63-
let sub = rosNode.subscribe({
64-
topic: '/my_topic',
65-
type: 'std_msgs/String',
66-
queueSize: 1,
67-
throttleMs: 1000},
68-
(data) => {
69-
console.log('SUB DATA ' + data.data);
74+
// EXP 5) Subscriber
75+
let sub = rosNode.subscribe({
76+
topic: '/my_topic',
77+
type: 'std_msgs/String',
78+
queueSize: 1,
79+
throttleMs: 1000},
80+
(data) => {
81+
console.log('SUB DATA ', data, data.data);
82+
});
7083
});
84+
7185
});
86+

index.js

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
const netUtils = require('./utils/network_utils.js');
2323
const msgUtils = require('./utils/message_utils.js');
24+
const messages = require('./utils/messages.js');
2425
msgUtils.findMessageFiles();
2526

2627
// these will be modules, they depend on logger which isn't initialized yet
@@ -136,6 +137,41 @@ let Rosnodejs = {
136137
return pack;
137138
},
138139

140+
/** get new object of the message class type for the given ROS
141+
* message type
142+
*/
143+
getMessage(type, cb) {
144+
messages.getMessage(type, function(error, Message) {
145+
// console.log(error, Message);
146+
if (error) {
147+
cb(error, null);
148+
} else {
149+
cb(null, new Message());
150+
}
151+
});
152+
},
153+
154+
/** create message classes for all the given types */
155+
use(types, callback) {
156+
var Messages = [];
157+
types.forEach(function(type) {
158+
messages.getMessage(type, function(error, Message) {
159+
Messages.push(Message);
160+
if (Messages.length === types.length) {
161+
callback();
162+
}
163+
});
164+
});
165+
},
166+
167+
/** get message definition class from registry. Do not generate it
168+
* from .msg file if it doesn't already exist. This is mostly
169+
* because that would need to be async right now and we want a sync
170+
* method. */
171+
message(type) {
172+
return messages.getMessageFromRegistry(type);
173+
},
174+
139175
/**
140176
* @return {NodeHandle} for initialized node
141177
*/

lib/Publisher.js

Lines changed: 49 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,11 @@
88
* You may obtain a copy of the License at
99
* http://www.apache.org/licenses/LICENSE-2.0
1010
*
11-
* Unless required by applicable law or agreed to in writing, software
12-
* distributed under the License is distributed on an "AS IS" BASIS,
13-
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14-
* See the License for the specific language governing permissions and
15-
* limitations under the License.
11+
* Unless required by applicable law or agreed to in writing,
12+
* software distributed under the License is distributed on an "AS
13+
* IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either
14+
* express or implied. See the License for the specific language
15+
* governing permissions and limitations under the License.
1616
*/
1717

1818
"use strict";
@@ -48,9 +48,11 @@ class Publisher extends EventEmitter {
4848
}
4949

5050
/**
51-
* throttleMs interacts with queueSize to determine when to send messages.
51+
* throttleMs interacts with queueSize to determine when to send
52+
* messages.
5253
* < 0 : send immediately - no interaction with queue
53-
* >= 0 : place event at end of event queue to publish message after minimum delay (MS)
54+
* >= 0 : place event at end of event queue to publish message
55+
after minimum delay (MS)
5456
*/
5557
if (options.hasOwnProperty('throttleMs')) {
5658
this._throttleMs = options.throttleMs;
@@ -118,7 +120,8 @@ class Publisher extends EventEmitter {
118120
}
119121

120122
/**
121-
* Schedule the msg for publishing - or publish immediately if we're supposed to
123+
* Schedule the msg for publishing - or publish immediately if we're
124+
* supposed to
122125
* @param msg {object} object type matching this._type
123126
* @param [throttleMs] {number} optional override for publisher setting
124127
*/
@@ -149,7 +152,8 @@ class Publisher extends EventEmitter {
149152
if (this._pubTimeout === null) {
150153
let now = Date.now();
151154
if (this._pubTime !== null) {
152-
// check how long to throttle for based on the last time we published
155+
// check how long to throttle for based on the last time we
156+
// published
153157
if (now - this._pubTime > throttleMs) {
154158
throttleMs = 0;
155159
}
@@ -180,11 +184,16 @@ class Publisher extends EventEmitter {
180184
try {
181185
let bufferInfo = {buffer: [], length: 0};
182186
// serialize pushes buffers onto buffInfo.buffer in order
183-
// concat them, and preprend the byte length to the message before sending
187+
// concat them, and preprend the byte length to the message
188+
// before sending
189+
// console.log("_publish", this._messageHandler, msg);
184190
bufferInfo = this._messageHandler.serialize(msg, bufferInfo);
191+
// bufferInfo = msg.serialize();
192+
// console.log("_publish", bufferInfo);
185193

186194
// prepend byte length to message
187-
let serialized = Serialize(Buffer.concat(bufferInfo.buffer, bufferInfo.length));
195+
let serialized = Serialize(
196+
Buffer.concat(bufferInfo.buffer, bufferInfo.length));
188197
Object.keys(this._subClients).forEach((client) => {
189198
this._subClients[client].write(serialized);
190199
});
@@ -197,7 +206,7 @@ class Publisher extends EventEmitter {
197206
}
198207
}
199208
catch (err) {
200-
this._log.warn('Error when publishing message ' + err);
209+
this._log.warn('Error when publishing message ', err.stack);
201210
}
202211
});
203212

@@ -212,13 +221,16 @@ class Publisher extends EventEmitter {
212221
NetworkUtils.getFreePort()
213222
.then((port) => {
214223
let server = net.createServer((subscriber) => {
215-
let subName = subscriber.remoteAddress + ":" + subscriber.remotePort;
224+
let subName = subscriber.remoteAddress + ":"
225+
+ subscriber.remotePort;
216226
subscriber.name = subName;
217-
this._log.debug('Publisher ' + this.getTopic() + ' got connection from ' + subName);
227+
this._log.debug('Publisher ' + this.getTopic()
228+
+ ' got connection from ' + subName);
218229

219-
// subscriber will send us tcpros handshake before we can start publishing
220-
// to it.
221-
subscriber.$handshake = this._handleHandshake.bind(this, subscriber);
230+
// subscriber will send us tcpros handshake before we can
231+
// start publishing to it.
232+
subscriber.$handshake =
233+
this._handleHandshake.bind(this, subscriber);
222234

223235
// handshake will be TCPROS encoded, so use a DeserializeStream to
224236
// handle any chunking
@@ -233,7 +245,8 @@ class Publisher extends EventEmitter {
233245
}
234246

235247
subscriber.on('close', () => {
236-
this._log.info('Publisher ' + this.getTopic() + ' client ' + subscriber.name + ' disconnected!');
248+
this._log.info('Publisher ' + this.getTopic() + ' client '
249+
+ subscriber.name + ' disconnected!');
237250
delete this._subClients[subscriber.name];
238251
});
239252

@@ -271,15 +284,24 @@ class Publisher extends EventEmitter {
271284
_handleHandshake(subscriber, data) {
272285
if (!subscriber.$initialized) {
273286
let header = TcprosUtils.parseSubHeader(data);
274-
let valid = TcprosUtils.validateSubHeader(header, this.getTopic(), this.getType(), this._messageHandler.md5sum());
287+
let valid = TcprosUtils.validateSubHeader(
288+
header, this.getTopic(), this.getType(),
289+
this._messageHandler.md5sum());
275290
if (valid !== null) {
276-
this._log.error('Unable to validate connection header ' + JSON.stringify(header));
291+
this._log.error('Unable to validate connection header '
292+
+ JSON.stringify(header));
277293
subscriber.write(Serialize(valid));
278294
return;
279295
}
280-
this._log.debug('Pub ' + this.getTopic() + ' got connection header ' + JSON.stringify(header));
281-
282-
let respHeader = TcprosUtils.createPubHeader(this._nodeHandle.getNodeName(), this._messageHandler.md5sum(), this.getType(), this.getLatching());
296+
this._log.debug('Pub ' + this.getTopic()
297+
+ ' got connection header ' + JSON.stringify(header));
298+
299+
let respHeader =
300+
TcprosUtils.createPubHeader(
301+
this._nodeHandle.getNodeName(),
302+
this._messageHandler.md5sum(),
303+
this.getType(),
304+
this.getLatching());
283305
subscriber.write(respHeader);
284306

285307
if (this._lastSentMsg !== null) {
@@ -293,7 +315,8 @@ class Publisher extends EventEmitter {
293315
this.emit('connection', subscriber.name);
294316
}
295317
else {
296-
this._log.error('Got message from subscriber after handshake - what gives!!');
318+
this._log.error(
319+
'Got message from subscriber after handshake - what gives!!');
297320
}
298321
}
299322

@@ -310,7 +333,8 @@ class Publisher extends EventEmitter {
310333
}
311334
})
312335
.catch((err, resp) => {
313-
this._log.error('reg pub err ' + err + ' resp: ' + JSON.stringify(resp));
336+
this._log.error('reg pub err ' + err + ' resp: '
337+
+ JSON.stringify(resp));
314338
})
315339
}
316340

package.json

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@
2121
"dependencies": {
2222
"moment": "^2.12.0",
2323
"portscanner": "^1.0.0",
24-
"xmlrpc": "^1.3.1"
24+
"xmlrpc": "^1.3.1",
25+
"walker" : "1.0.7",
26+
"md5" : "2.1.0",
27+
"async" : "0.1.22"
2528
}
2629
}

0 commit comments

Comments
 (0)