Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
49 changes: 24 additions & 25 deletions example.js
Original file line number Diff line number Diff line change
Expand Up @@ -7,21 +7,16 @@ const SetBool = rosnodejs.require('std_srvs').srv.SetBool;
rosnodejs.initNode('/my_node')
.then((rosNode) => {
// EXP 1) Service Server
let service = rosNode.advertiseService({
service: '/set_bool',
type: 'std_srvs/SetBool'
}, (req, resp) => {
console.log('Handling request! ' + JSON.stringify(req));
resp.success = !req.data;
resp.message = 'Inverted!';
return true;
let service = rosNode.advertiseService('/set_bool', SetBool,
(req, resp) => {
console.log('Handling request! ' + JSON.stringify(req));
resp.success = !req.data;
resp.message = 'Inverted!';
return true;
});

// EXP 2) Service Client
let serviceClient = rosNode.serviceClient({
service: '/set_bool',
type: 'std_srvs/SetBool'
});
let serviceClient = rosNode.serviceClient('/set_bool', 'std_srvs/SetBool');
rosNode.waitForService(serviceClient.getService(), 2000)
.then((available) => {
if (available) {
Expand All @@ -39,13 +34,13 @@ rosnodejs.initNode('/my_node')
});

// EXP 4) Publisher
let pub = rosNode.advertise({
topic: '/my_topic',
type: 'std_msgs/String',
queueSize: 1,
latching: true,
throttleMs: 9
});
let pub = rosNode.advertise( '/my_topic', std_msgs.String,
{
queueSize: 1,
latching: true,
throttleMs: 9
}
);

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

// EXP 5) Subscriber
let sub = rosNode.subscribe({
topic: '/my_topic',
type: 'std_msgs/String',
queueSize: 1,
throttleMs: 1000},
let sub = rosNode.subscribe('/my_topic', 'std_msgs/String',
(data) => {
console.log('SUB DATA ' + data.data);
});
},
{
queueSize: 1,
throttleMs: 1000
}
);
})
.catch((err) => {
console.log(err);
});
40 changes: 15 additions & 25 deletions example2.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ let rosnodejs = require('./index.js');
// const std_msgs = rosnodejs.require('std_msgs').msg;
// const SetBool = rosnodejs.require('std_srvs').srv.SetBool;

rosnodejs.use(['std_msgs/String'],
rosnodejs.use(['std_msgs/String'],
['std_srvs/SetBool'], function() {

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

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

// EXP 2) Service Client
setTimeout(function() {
let serviceClient = rosNode.serviceClient({
service: '/set_bool',
type: 'std_srvs/SetBool'
});
let serviceClient = rosNode.serviceClient('/set_bool','std_srvs/SetBool');
rosNode.waitForService(serviceClient.getService(), 2000)
.then((available) => {
if (available) {
const request =
new (rosnodejs.serviceRequest('std_srvs/SetBool'))({
const request =
new (rosnodejs.serviceRequest('std_srvs/SetBool'))({
data: false });
serviceClient.call(request, (resp) => {
console.log('Service response ' + JSON.stringify(resp));
});
} else {
console.log('Service not available');
console.log('Service not available');
}
});
}, 1000); // wait a second before calling our service

// EXP 3) Params
rosNode.setParam('~junk', {'hi': 2}).then(() => {
rosNode.getParam('~junk').then((val) => {
console.log('Got Param!!! ' + JSON.stringify(val));
rosNode.getParam('~junk').then((val) => {
console.log('Got Param!!! ' + JSON.stringify(val));
});
});

// // EXP 4) Publisher
let pub = rosNode.advertise({
topic: '/my_topic',
type: 'std_msgs/String',
let pub = rosNode.advertise('/my_topic','std_msgs/String', {
queueSize: 1,
latching: true,
throttleMs: 9
Expand All @@ -73,15 +66,12 @@ rosnodejs.use(['std_msgs/String'],
}, 5);

// EXP 5) Subscriber
let sub = rosNode.subscribe({
topic: '/my_topic',
type: 'std_msgs/String',
queueSize: 1,
throttleMs: 1000},
let sub = rosNode.subscribe('/my_topic', 'std_msgs/String',
(data) => {
console.log('SUB DATA ', data, data.data);
});
},
{queueSize: 1,
throttleMs: 1000});
});

});

});
8 changes: 6 additions & 2 deletions index.js
Original file line number Diff line number Diff line change
Expand Up @@ -149,8 +149,10 @@ let Rosnodejs = {
/** create message classes for all the given types */
_useMessages(types, callback) {
var Messages = [];
types.forEach(function(type) {
types.forEach(function(type) {
console.log('get message type! ' + type);
messages.getMessage(type, function(error, Message) {
console.log('got it!');
Messages.push(Message);
if (Messages.length === types.length) {
callback();
Expand All @@ -162,9 +164,11 @@ let Rosnodejs = {
/** create message classes for all the given types */
_useServices(types, callback) {
var count = types.length;
types.forEach(function(type) {
types.forEach(function(type) {
console.log('get service type! ' + type);
messages.getServiceRequest(type, function() {
messages.getServiceResponse(type, function() {
console.log('got it!');
if (--count == 0) {
callback();
}
Expand Down
38 changes: 13 additions & 25 deletions lib/ActionClient.js
Original file line number Diff line number Diff line change
Expand Up @@ -30,37 +30,25 @@ class ActionClient extends EventEmitter {
const nh = rosnodejs.nh;

// FIXME: support user options for these parameters
this._goalPub = nh.advertise({
topic: this._actionServer + '/goal',
type: this._actionType + 'Goal',
queueSize: 1
});
this._goalPub = nh.advertise(this._actionServer + '/goal', this._actionType + 'Goal',
{ queueSize: 1 });

this._cancelPub = nh.advertise({
topic: this._actionServer + '/goal',
type: 'actionlib_msgs/GoalID',
queueSize: 1
});
this._cancelPub = nh.advertise(this._actionServer + '/cancel', 'actionlib_msgs/GoalID',
{ queueSize: 1 });

this._statusSub = nh.subscribe({
topic: this._actionServer + '/status',
type: 'actionlib_msgs/GoalStatusArray',
queueSize: 1},
(msg) => { this._handleStatus(msg); }
this._statusSub = nh.subscribe(this._actionServer + '/status', 'actionlib_msgs/GoalStatusArray',
(msg) => { this._handleStatus(msg); },
{ queueSize: 1 }
);

this._feedbackSub = nh.subscribe({
topic: this._actionServer + '/feedback',
type: this._actionType + 'Feedback',
queueSize: 1},
(msg) => { this._handleFeedback(msg); }
this._feedbackSub = nh.subscribe(this._actionServer + '/feedback', this._actionType + 'Feedback',
(msg) => { this._handleFeedback(msg); },
{ queueSize: 1 }
);

this._statusSub = nh.subscribe({
topic: this._actionServer + '/result',
type: this._actionType + 'Result',
queueSize: 1},
(msg) => { this._handleResult(msg); }
this._statusSub = nh.subscribe(this._actionServer + '/result', this._actionType + 'Result',
(msg) => { this._handleResult(msg); },
{ queueSize: 1 }
);

this._goals = {};
Expand Down
97 changes: 71 additions & 26 deletions lib/NodeHandle.js
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
'use strict';

let RosNode = require('./RosNode.js');
const messageUtils = require('../utils/message_utils.js');

class NodeHandle {
constructor(node) {
Expand All @@ -36,52 +37,96 @@ class NodeHandle {
// Pubs, Subs, Services
//------------------------------------------------------------------
/**
* Create a ros publisher with the provided options
* @param options {object}
* @param options.topic {string} topic to publish on ('/chatter')
* @param options.type {string} type of message to publish ('std_msgs/String')
* @param options.latching {boolean} latch messages
* @param options.tpcNoDelay {boolean} set TCP no delay option on Socket
* @param options.queueSize {number} number of messages to queue when publishing
* @param options.throttleMs {number} milliseconds to throttle when publishing
* Creates a ros publisher with the provided options
* @param topic {string}
* @param type {string|Object} string representing message type or instance
* @param [options] {object}
* @param [options.latching] {boolean} latch messages
* @param [options.tpcNoDelay] {boolean} set TCP no delay option on Socket
* @param [options.queueSize] {number} number of messages to queue when publishing
* @param [options.throttleMs] {number} milliseconds to throttle when publishing
* @return {Publisher}
*/
advertise(options) {
advertise(topic, type, options) {
options = options || {};
options.topic = topic;
if (typeof type === 'string' || type instanceof String) {
options.type = type;
options.typeClass = messageUtils.getHandlerForMsgType(type);
}
else {
options.typeClass = type;
options.type = type.datatype();
}
return this._node.advertise(options);
}

/**
* Create a ros subscriber with the provided options
* @param options {object}
* @param options.topic {string} topic to publish on ('/chatter')
* @param options.type {string} type of message to publish ('std_msgs/String')
* @param options.queueSize {number} number of messages to queue when subscribing
* @param options.throttleMs {number} milliseconds to throttle when subscribing
* Creates a ros subscriber with the provided options
* @param topic {string}
* @param type {string|Object} string representing message type or instance
* @param callback {function} function to call when message is received
* @param [options] {object}
* @param [options.queueSize] {number} number of messages to queue when subscribing
* @param [options.throttleMs] {number} milliseconds to throttle when subscribing
* @return {Subscriber}
*/
subscribe(options, callback) {
subscribe(topic, type, callback, options) {
options = options || {};
options.topic = topic;
if (typeof type === 'string' || type instanceof String) {
options.type = type;
options.typeClass = messageUtils.getHandlerForMsgType(type);
}
else {
options.typeClass = type;
options.type = type.datatype();
}
return this._node.subscribe(options, callback);
}

/**
* Create a ros Service server with the provided options
* @param options {object}
* @param options.service {string} service to provide e.g ('/add_two_ints')
* @param options.type {string} type of service ('tutorial_msgs/AddTwoInts')
* Creates a ros Service server with the provided options
* @param service {string}
* @param type {string|Object} string representing service type or instance
* @param callback {function} function to call when this service is called
* e.g.
* (request, response) => {
* response.data = !request.data;
* return true;
* }
* @return {ServiceServer}
*/
advertiseService(options, callback) {
advertiseService(service, type, callback) {
let options = {service: service};
if (typeof type === 'string' || type instanceof String) {
options.type = type;
options.typeClass = messageUtils.getHandlerForSrvType(type);
}
else {
options.typeClass = type;
// TODO: this is not terribly robust...
options.type = type.Request.datatype().slice('Request'.length);
}
return this._node.advertiseService(options, callback);
}

/**
* Create a ros Service server with the provided options
* @param options {object}
* @param options.service {string} service to provide e.g ('/add_two_ints')
* @param options.type {string} type of service ('tutorial_msgs/AddTwoInts')
* Creates a ros Service client with the provided options
* @param service {string}
* @param type {string|Object} string representing service type or instance
* @return {ServiceClient}
*/
serviceClient(options) {
serviceClient(service, type) {
let options = {service: service};
if (typeof type === 'string' || type instanceof String) {
options.type = type;
options.typeClass = messageUtils.getHandlerForSrvType(type);
}
else {
options.typeClass = type;
options.type = type.Request.datatype().slice('Request'.length);
}
return this._node.serviceClient(options);
}

Expand Down
3 changes: 1 addition & 2 deletions lib/Publisher.js
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ let DeserializeStream = SerializationUtils.DeserializeStream;
let Deserialize = SerializationUtils.Deserialize;
let Serialize = SerializationUtils.Serialize;
let TcprosUtils = require('../utils/tcpros_utils.js');
let messageUtils = require('../utils/message_utils.js');
let EventEmitter = require('events');
let log = require('../utils/logger.js');

Expand Down Expand Up @@ -80,7 +79,7 @@ class Publisher extends EventEmitter {

this._server = null;

this._messageHandler = messageUtils.getHandlerForMsgType(this._type);
this._messageHandler = options.typeClass;

// messages published before this publisher
// was registered will be held here
Expand Down
Loading