Skip to content

Commit bfddfde

Browse files
Merge pull request #11 from RethinkRobotics-opensource/apiUpdate
Api update
2 parents 5cd9f11 + bcc7d55 commit bfddfde

15 files changed

+441
-296
lines changed

example.js

Lines changed: 24 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -7,21 +7,16 @@ const SetBool = rosnodejs.require('std_srvs').srv.SetBool;
77
rosnodejs.initNode('/my_node')
88
.then((rosNode) => {
99
// 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;
10+
let service = rosNode.advertiseService('/set_bool', SetBool,
11+
(req, resp) => {
12+
console.log('Handling request! ' + JSON.stringify(req));
13+
resp.success = !req.data;
14+
resp.message = 'Inverted!';
15+
return true;
1816
});
1917

2018
// EXP 2) Service Client
21-
let serviceClient = rosNode.serviceClient({
22-
service: '/set_bool',
23-
type: 'std_srvs/SetBool'
24-
});
19+
let serviceClient = rosNode.serviceClient('/set_bool', 'std_srvs/SetBool');
2520
rosNode.waitForService(serviceClient.getService(), 2000)
2621
.then((available) => {
2722
if (available) {
@@ -39,13 +34,13 @@ rosnodejs.initNode('/my_node')
3934
});
4035

4136
// 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-
});
37+
let pub = rosNode.advertise( '/my_topic', std_msgs.String,
38+
{
39+
queueSize: 1,
40+
latching: true,
41+
throttleMs: 9
42+
}
43+
);
4944

5045
let msgStart = 'my message ';
5146
let iter = 0;
@@ -60,12 +55,16 @@ rosnodejs.initNode('/my_node')
6055
}, 5);
6156

6257
// EXP 5) Subscriber
63-
let sub = rosNode.subscribe({
64-
topic: '/my_topic',
65-
type: 'std_msgs/String',
66-
queueSize: 1,
67-
throttleMs: 1000},
58+
let sub = rosNode.subscribe('/my_topic', 'std_msgs/String',
6859
(data) => {
6960
console.log('SUB DATA ' + data.data);
70-
});
61+
},
62+
{
63+
queueSize: 1,
64+
throttleMs: 1000
65+
}
66+
);
67+
})
68+
.catch((err) => {
69+
console.log(err);
7170
});

example2.js

Lines changed: 15 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ let rosnodejs = require('./index.js');
44
// const std_msgs = rosnodejs.require('std_msgs').msg;
55
// const SetBool = rosnodejs.require('std_srvs').srv.SetBool;
66

7-
rosnodejs.use(['std_msgs/String'],
7+
rosnodejs.use(['std_msgs/String'],
88
['std_srvs/SetBool'], function() {
99

1010
const msg = new (rosnodejs.message('std_msgs/String'))(
@@ -14,10 +14,8 @@ rosnodejs.use(['std_msgs/String'],
1414
.then((rosNode) => {
1515

1616
// EXP 1) Service Server
17-
let service = rosNode.advertiseService({
18-
service: '/set_bool',
19-
type: 'std_srvs/SetBool'
20-
}, (req, resp) => {
17+
let service = rosNode.advertiseService('/set_bool','std_srvs/SetBool',
18+
(req, resp) => {
2119
console.log('Handling request! ' + JSON.stringify(req));
2220
resp.success = !req.data;
2321
resp.message = 'Inverted!';
@@ -26,36 +24,31 @@ rosnodejs.use(['std_msgs/String'],
2624

2725
// EXP 2) Service Client
2826
setTimeout(function() {
29-
let serviceClient = rosNode.serviceClient({
30-
service: '/set_bool',
31-
type: 'std_srvs/SetBool'
32-
});
27+
let serviceClient = rosNode.serviceClient('/set_bool','std_srvs/SetBool');
3328
rosNode.waitForService(serviceClient.getService(), 2000)
3429
.then((available) => {
3530
if (available) {
36-
const request =
37-
new (rosnodejs.serviceRequest('std_srvs/SetBool'))({
31+
const request =
32+
new (rosnodejs.serviceRequest('std_srvs/SetBool'))({
3833
data: false });
3934
serviceClient.call(request, (resp) => {
4035
console.log('Service response ' + JSON.stringify(resp));
4136
});
4237
} else {
43-
console.log('Service not available');
38+
console.log('Service not available');
4439
}
4540
});
4641
}, 1000); // wait a second before calling our service
4742

4843
// EXP 3) Params
4944
rosNode.setParam('~junk', {'hi': 2}).then(() => {
50-
rosNode.getParam('~junk').then((val) => {
51-
console.log('Got Param!!! ' + JSON.stringify(val));
45+
rosNode.getParam('~junk').then((val) => {
46+
console.log('Got Param!!! ' + JSON.stringify(val));
5247
});
5348
});
5449

5550
// // EXP 4) Publisher
56-
let pub = rosNode.advertise({
57-
topic: '/my_topic',
58-
type: 'std_msgs/String',
51+
let pub = rosNode.advertise('/my_topic','std_msgs/String', {
5952
queueSize: 1,
6053
latching: true,
6154
throttleMs: 9
@@ -73,15 +66,12 @@ rosnodejs.use(['std_msgs/String'],
7366
}, 5);
7467

7568
// EXP 5) Subscriber
76-
let sub = rosNode.subscribe({
77-
topic: '/my_topic',
78-
type: 'std_msgs/String',
79-
queueSize: 1,
80-
throttleMs: 1000},
69+
let sub = rosNode.subscribe('/my_topic', 'std_msgs/String',
8170
(data) => {
8271
console.log('SUB DATA ', data, data.data);
83-
});
72+
},
73+
{queueSize: 1,
74+
throttleMs: 1000});
8475
});
85-
86-
});
8776

77+
});

index.js

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -149,8 +149,10 @@ let Rosnodejs = {
149149
/** create message classes for all the given types */
150150
_useMessages(types, callback) {
151151
var Messages = [];
152-
types.forEach(function(type) {
152+
types.forEach(function(type) {
153+
console.log('get message type! ' + type);
153154
messages.getMessage(type, function(error, Message) {
155+
console.log('got it!');
154156
Messages.push(Message);
155157
if (Messages.length === types.length) {
156158
callback();
@@ -162,9 +164,11 @@ let Rosnodejs = {
162164
/** create message classes for all the given types */
163165
_useServices(types, callback) {
164166
var count = types.length;
165-
types.forEach(function(type) {
167+
types.forEach(function(type) {
168+
console.log('get service type! ' + type);
166169
messages.getServiceRequest(type, function() {
167170
messages.getServiceResponse(type, function() {
171+
console.log('got it!');
168172
if (--count == 0) {
169173
callback();
170174
}

lib/ActionClient.js

Lines changed: 13 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -30,37 +30,25 @@ class ActionClient extends EventEmitter {
3030
const nh = rosnodejs.nh;
3131

3232
// FIXME: support user options for these parameters
33-
this._goalPub = nh.advertise({
34-
topic: this._actionServer + '/goal',
35-
type: this._actionType + 'Goal',
36-
queueSize: 1
37-
});
33+
this._goalPub = nh.advertise(this._actionServer + '/goal', this._actionType + 'Goal',
34+
{ queueSize: 1 });
3835

39-
this._cancelPub = nh.advertise({
40-
topic: this._actionServer + '/goal',
41-
type: 'actionlib_msgs/GoalID',
42-
queueSize: 1
43-
});
36+
this._cancelPub = nh.advertise(this._actionServer + '/cancel', 'actionlib_msgs/GoalID',
37+
{ queueSize: 1 });
4438

45-
this._statusSub = nh.subscribe({
46-
topic: this._actionServer + '/status',
47-
type: 'actionlib_msgs/GoalStatusArray',
48-
queueSize: 1},
49-
(msg) => { this._handleStatus(msg); }
39+
this._statusSub = nh.subscribe(this._actionServer + '/status', 'actionlib_msgs/GoalStatusArray',
40+
(msg) => { this._handleStatus(msg); },
41+
{ queueSize: 1 }
5042
);
5143

52-
this._feedbackSub = nh.subscribe({
53-
topic: this._actionServer + '/feedback',
54-
type: this._actionType + 'Feedback',
55-
queueSize: 1},
56-
(msg) => { this._handleFeedback(msg); }
44+
this._feedbackSub = nh.subscribe(this._actionServer + '/feedback', this._actionType + 'Feedback',
45+
(msg) => { this._handleFeedback(msg); },
46+
{ queueSize: 1 }
5747
);
5848

59-
this._statusSub = nh.subscribe({
60-
topic: this._actionServer + '/result',
61-
type: this._actionType + 'Result',
62-
queueSize: 1},
63-
(msg) => { this._handleResult(msg); }
49+
this._statusSub = nh.subscribe(this._actionServer + '/result', this._actionType + 'Result',
50+
(msg) => { this._handleResult(msg); },
51+
{ queueSize: 1 }
6452
);
6553

6654
this._goals = {};

lib/NodeHandle.js

Lines changed: 71 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
'use strict';
1919

2020
let RosNode = require('./RosNode.js');
21+
const messageUtils = require('../utils/message_utils.js');
2122

2223
class NodeHandle {
2324
constructor(node) {
@@ -36,52 +37,96 @@ class NodeHandle {
3637
// Pubs, Subs, Services
3738
//------------------------------------------------------------------
3839
/**
39-
* Create a ros publisher with the provided options
40-
* @param options {object}
41-
* @param options.topic {string} topic to publish on ('/chatter')
42-
* @param options.type {string} type of message to publish ('std_msgs/String')
43-
* @param options.latching {boolean} latch messages
44-
* @param options.tpcNoDelay {boolean} set TCP no delay option on Socket
45-
* @param options.queueSize {number} number of messages to queue when publishing
46-
* @param options.throttleMs {number} milliseconds to throttle when publishing
40+
* Creates a ros publisher with the provided options
41+
* @param topic {string}
42+
* @param type {string|Object} string representing message type or instance
43+
* @param [options] {object}
44+
* @param [options.latching] {boolean} latch messages
45+
* @param [options.tpcNoDelay] {boolean} set TCP no delay option on Socket
46+
* @param [options.queueSize] {number} number of messages to queue when publishing
47+
* @param [options.throttleMs] {number} milliseconds to throttle when publishing
4748
* @return {Publisher}
4849
*/
49-
advertise(options) {
50+
advertise(topic, type, options) {
51+
options = options || {};
52+
options.topic = topic;
53+
if (typeof type === 'string' || type instanceof String) {
54+
options.type = type;
55+
options.typeClass = messageUtils.getHandlerForMsgType(type);
56+
}
57+
else {
58+
options.typeClass = type;
59+
options.type = type.datatype();
60+
}
5061
return this._node.advertise(options);
5162
}
5263

5364
/**
54-
* Create a ros subscriber with the provided options
55-
* @param options {object}
56-
* @param options.topic {string} topic to publish on ('/chatter')
57-
* @param options.type {string} type of message to publish ('std_msgs/String')
58-
* @param options.queueSize {number} number of messages to queue when subscribing
59-
* @param options.throttleMs {number} milliseconds to throttle when subscribing
65+
* Creates a ros subscriber with the provided options
66+
* @param topic {string}
67+
* @param type {string|Object} string representing message type or instance
68+
* @param callback {function} function to call when message is received
69+
* @param [options] {object}
70+
* @param [options.queueSize] {number} number of messages to queue when subscribing
71+
* @param [options.throttleMs] {number} milliseconds to throttle when subscribing
6072
* @return {Subscriber}
6173
*/
62-
subscribe(options, callback) {
74+
subscribe(topic, type, callback, options) {
75+
options = options || {};
76+
options.topic = topic;
77+
if (typeof type === 'string' || type instanceof String) {
78+
options.type = type;
79+
options.typeClass = messageUtils.getHandlerForMsgType(type);
80+
}
81+
else {
82+
options.typeClass = type;
83+
options.type = type.datatype();
84+
}
6385
return this._node.subscribe(options, callback);
6486
}
6587

6688
/**
67-
* Create a ros Service server with the provided options
68-
* @param options {object}
69-
* @param options.service {string} service to provide e.g ('/add_two_ints')
70-
* @param options.type {string} type of service ('tutorial_msgs/AddTwoInts')
89+
* Creates a ros Service server with the provided options
90+
* @param service {string}
91+
* @param type {string|Object} string representing service type or instance
92+
* @param callback {function} function to call when this service is called
93+
* e.g.
94+
* (request, response) => {
95+
* response.data = !request.data;
96+
* return true;
97+
* }
7198
* @return {ServiceServer}
7299
*/
73-
advertiseService(options, callback) {
100+
advertiseService(service, type, callback) {
101+
let options = {service: service};
102+
if (typeof type === 'string' || type instanceof String) {
103+
options.type = type;
104+
options.typeClass = messageUtils.getHandlerForSrvType(type);
105+
}
106+
else {
107+
options.typeClass = type;
108+
// TODO: this is not terribly robust...
109+
options.type = type.Request.datatype().slice('Request'.length);
110+
}
74111
return this._node.advertiseService(options, callback);
75112
}
76113

77114
/**
78-
* Create a ros Service server with the provided options
79-
* @param options {object}
80-
* @param options.service {string} service to provide e.g ('/add_two_ints')
81-
* @param options.type {string} type of service ('tutorial_msgs/AddTwoInts')
115+
* Creates a ros Service client with the provided options
116+
* @param service {string}
117+
* @param type {string|Object} string representing service type or instance
82118
* @return {ServiceClient}
83119
*/
84-
serviceClient(options) {
120+
serviceClient(service, type) {
121+
let options = {service: service};
122+
if (typeof type === 'string' || type instanceof String) {
123+
options.type = type;
124+
options.typeClass = messageUtils.getHandlerForSrvType(type);
125+
}
126+
else {
127+
options.typeClass = type;
128+
options.type = type.Request.datatype().slice('Request'.length);
129+
}
85130
return this._node.serviceClient(options);
86131
}
87132

lib/Publisher.js

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@ let DeserializeStream = SerializationUtils.DeserializeStream;
2424
let Deserialize = SerializationUtils.Deserialize;
2525
let Serialize = SerializationUtils.Serialize;
2626
let TcprosUtils = require('../utils/tcpros_utils.js');
27-
let messageUtils = require('../utils/message_utils.js');
2827
let EventEmitter = require('events');
2928
let log = require('../utils/logger.js');
3029

@@ -80,7 +79,7 @@ class Publisher extends EventEmitter {
8079

8180
this._server = null;
8281

83-
this._messageHandler = messageUtils.getHandlerForMsgType(this._type);
82+
this._messageHandler = options.typeClass;
8483

8584
// messages published before this publisher
8685
// was registered will be held here

0 commit comments

Comments
 (0)