Skip to content

Commit 736f8fc

Browse files
committed
Now computing service md5sums correctly
- Fixes #24. - Replaces PR #22. - Refactored the file parsing code a bit in the process; a little cleaner now. Testing use of actionlib topic with turtlesim - now using a patched version of xmlrpc that sends content-length headers on method responses. This omission was preventing tutlesim from receiving publications from rosnodejs, and hence also action lib calls. Simplified construction of complex messages - can now provide all data, incl. for sub-messages, directly in message constructor. E.g.: ```js let now = Date.now(); let secs = parseInt(now/1000); let nsecs = (now % 1000) * 1000; let shapeMsg = new shapeActionGoal({ header: { seq: 0, stamp: { secs: secs, nsecs: nsecs }, frame_id: '' }, goal_id: { stamp: { secs: secs, nsecs: nsecs }, id: "/my_node-1-"+secs+"."+nsecs+"000" }, goal: { edges: 5, radius: 1 } }); ``` Example of working with turtlesim
1 parent 184c867 commit 736f8fc

File tree

7 files changed

+369
-183
lines changed

7 files changed

+369
-183
lines changed

example_turtle.js

Lines changed: 118 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,118 @@
1+
'use strict';
2+
3+
let rosnodejs = require('./index.js');
4+
5+
rosnodejs.initNode('/my_node', {
6+
messages: [
7+
'rosgraph_msgs/Log', // required for new logging approach
8+
'turtlesim/Pose',
9+
'turtle_actionlib/ShapeActionGoal',
10+
'geometry_msgs/Twist'
11+
],
12+
services: ['std_srvs/SetBool', "turtlesim/TeleportRelative"]
13+
}).then((rosNode) => {
14+
15+
// ---------------------------------------------------------
16+
// Service Call
17+
18+
const TeleportRelative = rosnodejs.require('turtlesim').srv.TeleportRelative;
19+
const teleport_request = new TeleportRelative.Request({
20+
linear: 0.1,
21+
angular: 0.0
22+
});
23+
24+
let serviceClient2 = rosNode.serviceClient("/turtle1/teleport_relative",
25+
"turtlesim/TeleportRelative");
26+
rosNode.waitForService(serviceClient2.getService(), 2000)
27+
.then((available) => {
28+
if (available) {
29+
serviceClient2.call(teleport_request, (resp) => {
30+
console.log('Service response ' + JSON.stringify(resp));
31+
});
32+
} else {
33+
console.log('Service not available');
34+
}
35+
});
36+
37+
38+
// ---------------------------------------------------------
39+
// Subscribe
40+
rosNode.subscribe(
41+
'/turtle1/pose',
42+
'turtlesim/Pose',
43+
(data) => {
44+
console.log('pose', data);
45+
},
46+
{queueSize: 1,
47+
throttleMs: 1000});
48+
49+
// ---------------------------------------------------------
50+
// Publish
51+
// equivalent to:
52+
// rostopic pub /turtle1/cmd_vel geometry_msgs/Twist '[1, 0, 0]' '[0, 0, 0]'
53+
// sudo tcpdump -ASs 0 -i lo | tee tmp/rostopic.dump
54+
let cmd_vel = rosNode.advertise('/turtle1/cmd_vel','geometry_msgs/Twist', {
55+
queueSize: 1,
56+
latching: true,
57+
throttleMs: 9
58+
});
59+
cmd_vel.on('registered', function() {
60+
console.log("registered");
61+
const Twist = rosnodejs.require('geometry_msgs').msg.Twist;
62+
const msgTwist = new Twist();
63+
msgTwist.linear = new (rosnodejs.require('geometry_msgs').msg.Vector3)();
64+
msgTwist.linear.x = 1;
65+
msgTwist.linear.y = 0;
66+
msgTwist.linear.z = 0;
67+
msgTwist.angular = new (rosnodejs.require('geometry_msgs').msg.Vector3)();
68+
msgTwist.angular.x = 0;
69+
msgTwist.angular.y = 0;
70+
msgTwist.angular.z = 0;
71+
console.log("Twist", msgTwist);
72+
cmd_vel.publish(msgTwist);
73+
});
74+
cmd_vel.on('connection', function(s) {
75+
console.log("connected", s);
76+
});
77+
78+
79+
// ---------------------------------------------------------
80+
// test actionlib
81+
// rosrun turtlesim turtlesim_node
82+
// rosrun turtle_actionlib shape_server
83+
84+
let pub_action =
85+
rosNode.advertise('/turtle_shape/goal', 'turtle_actionlib/ShapeActionGoal', {
86+
queueSize: 1,
87+
latching: true,
88+
throttleMs: 9
89+
});
90+
91+
let shapeActionGoal = rosnodejs.require('turtle_actionlib').msg.ShapeActionGoal;
92+
console.log("shapeMsgGoal", shapeActionGoal);
93+
let now = Date.now();
94+
let secs = parseInt(now/1000);
95+
let nsecs = (now % 1000) * 1000;
96+
let shapeMsg = new shapeActionGoal({
97+
header: {
98+
seq: 0,
99+
stamp: new Date(),
100+
frame_id: ''
101+
},
102+
goal_id: {
103+
stamp: new Date(),
104+
id: "/my_node-1-"+secs+"."+nsecs+"000"
105+
},
106+
goal: {
107+
edges: 5,
108+
radius: 1
109+
}
110+
});
111+
112+
console.log("shapeMsg", shapeMsg);
113+
pub_action.publish(shapeMsg);
114+
115+
console.log("\n** done\n");
116+
117+
118+
});

index.js

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -172,11 +172,8 @@ let Rosnodejs = {
172172
const self = this;
173173
return new Promise((resolve, reject) => {
174174
self._useMessages(messages)
175-
.then(() => {
176-
return self._useServices(services);
177-
}).then(() => {
178-
resolve();
179-
});
175+
.then(() => { return self._useServices(services); })
176+
.then(() => { resolve(); });
180177
});
181178
},
182179

@@ -197,20 +194,18 @@ let Rosnodejs = {
197194
});
198195
},
199196

200-
/** create message classes for all the given types */
197+
/** create service classes for all the given types */
201198
_useServices(types) {
202199
if (!types || types.length == 0) {
203200
return Promise.resolve();
204201
}
205202
var count = types.length;
206203
return new Promise((resolve, reject) => {
207204
types.forEach(function(type) {
208-
messages.getServiceRequest(type, function() {
209-
messages.getServiceResponse(type, function() {
210-
if (--count == 0) {
211-
resolve();
212-
}
213-
});
205+
messages.getService(type, function() {
206+
if (--count == 0) {
207+
resolve();
208+
}
214209
});
215210
});
216211
});

lib/Publisher.js

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -177,10 +177,8 @@ class Publisher extends EventEmitter {
177177
// serialize pushes buffers onto buffInfo.buffer in order
178178
// concat them, and preprend the byte length to the message
179179
// before sending
180-
// console.log("_publish", this._messageHandler, msg);
181180
bufferInfo = this._messageHandler.serialize(msg, bufferInfo);
182181
// bufferInfo = msg.serialize();
183-
// console.log("_publish", bufferInfo);
184182

185183
// prepend byte length to message
186184
let serialized = Serialize(

package.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
"dependencies": {
2525
"moment": "2.12.0",
2626
"portscanner": "1.0.0",
27-
"xmlrpc": "1.3.1",
27+
"xmlrpc": "chfritz/node-xmlrpc",
2828
"walker" : "1.0.7",
2929
"md5" : "2.1.0",
3030
"async" : "0.1.22",

utils/fields.js

Lines changed: 27 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,26 @@ fields.parsePrimitive = function(fieldType, fieldValue) {
7676
else if (fieldType === 'float64') {
7777
parsedValue = parseFloat(fieldValue);
7878
}
79+
else if (fieldType === 'time') {
80+
var now;
81+
if (fieldValue.secs && fieldValue.nsecs) {
82+
parsedValue.secs = fieldValue.secs;
83+
parsedValue.nsecs = fieldValue.nsecs;
84+
} else {
85+
if (fieldValue instanceof Date) {
86+
now = fieldValue.getTime();
87+
} else if (typeof fieldValue == "number") {
88+
now = fieldValue;
89+
} else {
90+
now = Date.now();
91+
}
92+
var secs = parseInt(now/1000);
93+
var nsecs = (now % 1000) * 1000;
94+
95+
parsedValue.secs = secs;
96+
parsedValue.nsecs = nsecs;
97+
}
98+
}
7999

80100
return parsedValue;
81101
};
@@ -120,6 +140,11 @@ fields.serializePrimitive =
120140
bufferOffset += 4;
121141
buffer.write(fieldValue, bufferOffset, 'ascii');
122142
}
143+
else if (fieldType === 'time') {
144+
buffer.writeUInt32LE(fieldValue.secs, bufferOffset);
145+
buffer.writeUInt32LE(fieldValue.nsecs, bufferOffset+4);
146+
}
147+
123148
}
124149

125150
fields.deserializePrimitive = function(fieldType, buffer, bufferOffset) {
@@ -251,10 +276,10 @@ fields.getArraySize = function(arrayType, array) {
251276
fields.getMessageSize = function(message) {
252277
var that = this
253278
, messageSize = 0
254-
, fields = message.fields
279+
, innerfields = message.fields
255280
;
256281

257-
fields.forEach(function(field) {
282+
innerfields.forEach(function(field) {
258283
var fieldValue = message[field.name];
259284
if (that.isPrimitive(field.type)) {
260285
messageSize += that.getPrimitiveSize(field.type, fieldValue);

0 commit comments

Comments
 (0)