Skip to content

Commit 1a22dd6

Browse files
committed
ActionClient: export it and added cancel
- Added getActionClient to Rosnodejs (previously the action client wasn't exported in any way) - ActionClient: added "cancel" function
1 parent e6cd037 commit 1a22dd6

File tree

3 files changed

+48
-10
lines changed

3 files changed

+48
-10
lines changed

example_turtle.js

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@
77
'use strict';
88

99
let rosnodejs = require('./index.js');
10-
const ActionClient = require('./lib/ActionClient.js');
11-
1210
rosnodejs.initNode('/my_node', {onTheFly: true}).then((rosNode) => {
1311

1412
// get list of existing publishers, subscribers, and services
@@ -77,7 +75,7 @@ rosnodejs.initNode('/my_node', {onTheFly: true}).then((rosNode) => {
7775
// wait two seconds for previous example to complete
7876
setTimeout(function() {
7977
let shapeActionGoal = rosnodejs.require('turtle_actionlib').msg.ShapeActionGoal;
80-
let ac = new ActionClient({
78+
let ac = rosnodejs.getActionClient({
8179
type: "turtle_actionlib/ShapeAction",
8280
actionServer: "/turtle_shape"
8381
});
@@ -87,6 +85,9 @@ rosnodejs.initNode('/my_node', {onTheFly: true}).then((rosNode) => {
8785
radius: 1
8886
}
8987
}));
88+
setTimeout(function() {
89+
ac.cancel();
90+
}, 1000);
9091
}, 2000);
9192

9293
// ---------------------------------------------------------

index.js

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ const LogFormatter = require('./utils/log/LogFormatter.js');
2929
const RosNode = require('./lib/RosNode.js');
3030
const NodeHandle = require('./lib/NodeHandle.js');
3131
const Logging = require('./lib/Logging.js');
32+
const ActionClient = require('./lib/ActionClient.js');
3233

3334
msgUtils.findMessageFiles();
3435

@@ -216,6 +217,29 @@ let Rosnodejs = {
216217
console: ConsoleLogStream,
217218
ros: RosLogStream
218219
}
220+
},
221+
222+
223+
//------------------------------------------------------------------
224+
// ActionLib
225+
//------------------------------------------------------------------
226+
227+
/**
228+
Get an action client for a given type and action server.
229+
230+
Example:
231+
let ac = rosNode.getActionClient({
232+
type: "turtle_actionlib/ShapeAction",
233+
actionServer: "/turtle_shape"
234+
});
235+
let shapeActionGoal =
236+
rosnodejs.require('turtle_actionlib').msg.ShapeActionGoal;
237+
ac.sendGoal(new shapeActionGoal({
238+
goal: { edges: 3, radius: 1 } }));
239+
*/
240+
getActionClient(options) {
241+
options.rosnodejs = Rosnodejs;
242+
return new ActionClient(options);
219243
}
220244
}
221245

lib/ActionClient.js

Lines changed: 20 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717

1818
'use strict';
1919

20-
const rosnodejs = require('../index.js');
2120
const timeUtils = require('../utils/time_utils.js');
2221
let EventEmitter = require('events');
2322

@@ -29,28 +28,29 @@ class ActionClient extends EventEmitter {
2928

3029
this._actionServer = options.actionServer;
3130

32-
const nh = rosnodejs.nh;
31+
this._rosnodejs = options.rosnodejs;
32+
const nh = this._rosnodejs.getNodeHandle();
3333

3434
// FIXME: support user options for these parameters
35-
this._goalPub = nh.advertise(this._actionServer + '/goal',
35+
this._goalPub = nh.advertise(this._actionServer + '/goal',
3636
this._actionType + 'Goal',
3737
{ queueSize: 1, latching: true });
3838

39-
this._cancelPub = nh.advertise(this._actionServer + '/cancel',
39+
this._cancelPub = nh.advertise(this._actionServer + '/cancel',
4040
'actionlib_msgs/GoalID',
4141
{ queueSize: 1, latching: true });
4242

43-
this._statusSub = nh.subscribe(this._actionServer + '/status',
43+
this._statusSub = nh.subscribe(this._actionServer + '/status',
4444
'actionlib_msgs/GoalStatusArray',
4545
(msg) => { this._handleStatus(msg); },
4646
{ queueSize: 1 } );
4747

48-
this._feedbackSub = nh.subscribe(this._actionServer + '/feedback',
48+
this._feedbackSub = nh.subscribe(this._actionServer + '/feedback',
4949
this._actionType + 'Feedback',
5050
(msg) => { this._handleFeedback(msg); },
5151
{ queueSize: 1 } );
5252

53-
this._statusSub = nh.subscribe(this._actionServer + '/result',
53+
this._statusSub = nh.subscribe(this._actionServer + '/result',
5454
this._actionType + 'Result',
5555
(msg) => { this._handleResult(msg); },
5656
{ queueSize: 1 } );
@@ -97,6 +97,19 @@ class ActionClient extends EventEmitter {
9797
this._goals[goalId] = goal;
9898

9999
this._goalPub.publish(goal);
100+
return goal;
101+
}
102+
103+
/** Cancel the given goal. If none is given, send an empty goal message,
104+
i.e. cancel all goals. See
105+
http://wiki.ros.org/actionlib/DetailedDescription#The_Messages
106+
*/
107+
cancel(goal) {
108+
if (!goal) {
109+
let GoalID = this._rosnodejs.require('actionlib_msgs').msg.GoalID;
110+
goal = new GoalID();
111+
}
112+
this._cancelPub.publish(goal);
100113
}
101114

102115
_generateGoalId() {

0 commit comments

Comments
 (0)