Skip to content

Commit 161461c

Browse files
committed
Reformatting, tests, bugs
-Basic genjs tests -Update msg include method -Previously, rosjs would load all message files it could find at init. Instead, it will now find all the paths it expects to include from and cache them. Message packages are required through rosjs instead of through the default 'requires' method according to these paths. -Fixes npm tests for new require method -Fixes bug on publisher disconnect -Moves test.js to better-named example.js
1 parent 4fe585c commit 161461c

20 files changed

Lines changed: 1941 additions & 1617 deletions

test.js renamed to example.js

Lines changed: 15 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,29 +1,33 @@
11
'use strict';
22

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

57
rosjs.initNode('/my_node')
68
.then((rosNode) => {
7-
console.log('GOTIT');
89
// EXP 1) Service Server
910
let service = rosNode.advertiseService({
10-
service: '/list_cameras',
11-
type: 'baxter_core_msgs/ListCameras'
11+
service: '/set_bool',
12+
type: 'std_srvs/SetBool'
1213
}, (req, resp) => {
1314
console.log('Handling request! ' + JSON.stringify(req));
14-
resp.cameras = ['right_hand_camera', 'left_hand_camera', 'head_camera'];
15+
resp.success = !req.data;
16+
resp.message = 'Inverted!';
1517
return true;
1618
});
1719

1820
// EXP 2) Service Client
1921
let serviceClient = rosNode.serviceClient({
20-
service: '/list_cameras',
21-
type: 'baxter_core_msgs/ListCameras'
22+
service: '/set_bool',
23+
type: 'std_srvs/SetBool'
2224
});
2325
rosNode.waitForService(serviceClient.getService(), 2000)
2426
.then((available) => {
2527
if (available) {
26-
serviceClient.call({}, (resp) => {
28+
const request = new SetBool.Request();
29+
request.data = true;
30+
serviceClient.call(request, (resp) => {
2731
console.log('Service response ' + JSON.stringify(resp));
2832
});
2933
}
@@ -40,15 +44,15 @@ rosjs.initNode('/my_node')
4044
type: 'std_msgs/String',
4145
queueSize: 1,
4246
latching: true,
43-
throttleMs: 100
47+
throttleMs: 9
4448
});
4549

4650
let msgStart = 'my message ';
4751
let iter = 0;
52+
const msg = new std_msgs.String();
4853
setInterval(() => {
49-
pub.publish({
50-
data: msgStart + iter
51-
});
54+
msg.data = msgStart + iter
55+
pub.publish(msg);
5256
++iter;
5357
if (iter > 200) {
5458
iter = 0;

index.js

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
//------------------------------------------------------------------
2121

2222
const netUtils = require('./utils/network_utils.js');
23+
const msgUtils = require('./utils/message_utils.js');
24+
msgUtils.findMessageFiles();
2325

2426
// these will be modules, they depend on logger which isn't initialized yet
2527
// though so they'll be required later (in initNode)
@@ -111,20 +113,29 @@ let Rosjs = {
111113
// require other necessary modules...
112114
RosNode = require('./lib/RosNode.js');
113115
NodeHandle = require('./lib/NodeHandle.js');
114-
let message_utils = require('./utils/message_utils.js');
115-
116-
// load all message files
117-
message_utils.loadMessageFiles();
118116

119117
// create the ros node. Return a promise that will
120118
// resolve when connection to master is established
121119
let checkMasterTimeout = 0;
122120
rosNode = new RosNode(nodeName, rosMasterUri);
123121
return new Promise((resolve, reject) => {
124122
_checkMasterHelper(resolve, 0);
123+
})
124+
.catch((err) => {
125+
log.error('Error: ' + err);
125126
});
126127
},
127128

129+
require(msgPackage) {
130+
let pack = msgUtils.getPackage(msgPackage);
131+
if (!pack) {
132+
msgUtils.loadMessagePackage(msgPackage);
133+
return msgUtils.getPackage(msgPackage);
134+
}
135+
// else
136+
return pack;
137+
},
138+
128139
/**
129140
* @return {NodeHandle} for initialized node
130141
*/

lib/MasterApiClient.js

Lines changed: 117 additions & 117 deletions
Original file line numberDiff line numberDiff line change
@@ -26,123 +26,123 @@ let xmlrpcUtils = require('../utils/xmlrpc_utils.js');
2626

2727
class MasterApiClient {
2828

29-
constructor(rosMasterUri, logName) {
30-
this._log = logger.createLogger({name: logName});
31-
this._log.info('Connecting to ROS Master at ' + rosMasterUri);
32-
this._xmlrpcClient = xmlrpc.createClient(networkUtils.getAddressAndPortFromUri(rosMasterUri));
33-
};
34-
35-
getXmlrpcClient() {
36-
return this._xmlrpcClient;
37-
}
38-
39-
_call(method, data, resolve, reject) {
40-
xmlrpcUtils.call(this.getXmlrpcClient(), method, data, resolve, reject, this._log);
41-
}
42-
43-
registerService(callerId, service, serviceUri, uri) {
44-
let data = [
45-
callerId,
46-
service,
47-
serviceUri,
48-
uri
49-
];
50-
51-
return new Promise((resolve, reject) => {
52-
this._call('registerService', data, resolve, reject);
53-
});
54-
}
55-
56-
unregisterService(callerId, service, serviceUri) {
57-
let data = [
58-
callerId,
59-
service,
60-
serviceUri
61-
];
62-
63-
return new Promise((resolve, reject) => {
64-
this._call('unregisterService', data, resolve, reject);
65-
});
66-
}
67-
68-
registerSubscriber(callerId, topic, topicType, uri) {
69-
let data = [
70-
callerId,
71-
topic,
72-
topicType,
73-
uri
74-
];
75-
return new Promise((resolve, reject) => {
76-
this._call('registerSubscriber', data, resolve, reject);
77-
});
78-
}
79-
80-
unregisterSubscriber(callerId, topic, uri) {
81-
let data = [
82-
callerId,
83-
topic,
84-
uri
85-
];
86-
return new Promise((resolve, reject) => {
87-
this._call('unregisterSubscriber', data, resolve, reject);
88-
});
89-
}
90-
91-
registerPublisher(callerId, topic, topicType, uri) {
92-
let data = [
93-
callerId,
94-
topic,
95-
topicType,
96-
uri
97-
];
98-
return new Promise((resolve, reject) => {
99-
this._call('registerPublisher', data, resolve, reject);
100-
});
101-
}
102-
103-
unregisterPublisher(callerId, topic, uri) {
104-
let data = [
105-
callerId,
106-
topic,
107-
uri
108-
];
109-
return new Promise((resolve, reject) => {
110-
this._call('unregisterPublisher', data, resolve, reject);
111-
});
112-
}
113-
114-
lookupNode(callerId, nodeName) {
115-
let data = [callerId, nodeName];
116-
return new Promise((resolve, reject) => {
117-
this._call('lookupNode', data, resolve, reject);
118-
});
119-
}
120-
121-
getPublishedTopics(callerId, subgraph) {
122-
throw new Error('NOT SUPPORTED');
123-
}
124-
125-
getTopicTypes(callerId) {
126-
throw new Error('NOT SUPPORTED');
127-
}
128-
129-
getSystemState(callerId) {
130-
throw new Error('NOT SUPPORTED');
131-
}
132-
133-
getUri(callerId) {
134-
let data = [callerId];
135-
return new Promise((resolve, reject) => {
136-
this._call('getUri', data, resolve, reject);
137-
});
138-
}
139-
140-
lookupService(callerId, service) {
141-
let data = [callerId, service];
142-
return new Promise((resolve, reject) => {
143-
this._call('lookupService', data, resolve, reject);
144-
});
145-
}
29+
constructor(rosMasterUri, logName) {
30+
this._log = logger.createLogger({name: logName});
31+
this._log.info('Connecting to ROS Master at ' + rosMasterUri);
32+
this._xmlrpcClient = xmlrpc.createClient(networkUtils.getAddressAndPortFromUri(rosMasterUri));
33+
};
34+
35+
getXmlrpcClient() {
36+
return this._xmlrpcClient;
37+
}
38+
39+
_call(method, data, resolve, reject) {
40+
xmlrpcUtils.call(this.getXmlrpcClient(), method, data, resolve, reject, this._log);
41+
}
42+
43+
registerService(callerId, service, serviceUri, uri) {
44+
let data = [
45+
callerId,
46+
service,
47+
serviceUri,
48+
uri
49+
];
50+
51+
return new Promise((resolve, reject) => {
52+
this._call('registerService', data, resolve, reject);
53+
});
54+
}
55+
56+
unregisterService(callerId, service, serviceUri) {
57+
let data = [
58+
callerId,
59+
service,
60+
serviceUri
61+
];
62+
63+
return new Promise((resolve, reject) => {
64+
this._call('unregisterService', data, resolve, reject);
65+
});
66+
}
67+
68+
registerSubscriber(callerId, topic, topicType, uri) {
69+
let data = [
70+
callerId,
71+
topic,
72+
topicType,
73+
uri
74+
];
75+
return new Promise((resolve, reject) => {
76+
this._call('registerSubscriber', data, resolve, reject);
77+
});
78+
}
79+
80+
unregisterSubscriber(callerId, topic, uri) {
81+
let data = [
82+
callerId,
83+
topic,
84+
uri
85+
];
86+
return new Promise((resolve, reject) => {
87+
this._call('unregisterSubscriber', data, resolve, reject);
88+
});
89+
}
90+
91+
registerPublisher(callerId, topic, topicType, uri) {
92+
let data = [
93+
callerId,
94+
topic,
95+
topicType,
96+
uri
97+
];
98+
return new Promise((resolve, reject) => {
99+
this._call('registerPublisher', data, resolve, reject);
100+
});
101+
}
102+
103+
unregisterPublisher(callerId, topic, uri) {
104+
let data = [
105+
callerId,
106+
topic,
107+
uri
108+
];
109+
return new Promise((resolve, reject) => {
110+
this._call('unregisterPublisher', data, resolve, reject);
111+
});
112+
}
113+
114+
lookupNode(callerId, nodeName) {
115+
let data = [callerId, nodeName];
116+
return new Promise((resolve, reject) => {
117+
this._call('lookupNode', data, resolve, reject);
118+
});
119+
}
120+
121+
getPublishedTopics(callerId, subgraph) {
122+
throw new Error('NOT SUPPORTED');
123+
}
124+
125+
getTopicTypes(callerId) {
126+
throw new Error('NOT SUPPORTED');
127+
}
128+
129+
getSystemState(callerId) {
130+
throw new Error('NOT SUPPORTED');
131+
}
132+
133+
getUri(callerId) {
134+
let data = [callerId];
135+
return new Promise((resolve, reject) => {
136+
this._call('getUri', data, resolve, reject);
137+
});
138+
}
139+
140+
lookupService(callerId, service) {
141+
let data = [callerId, service];
142+
return new Promise((resolve, reject) => {
143+
this._call('lookupService', data, resolve, reject);
144+
});
145+
}
146146
};
147147

148148
//-----------------------------------------------------------------------

0 commit comments

Comments
 (0)