forked from RobotWebTools/roslibjs
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathActionClient.js
132 lines (115 loc) · 3.65 KB
/
ActionClient.js
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
/**
* @fileOverview
* @author Russell Toris - [email protected]
*/
var Topic = require('../core/Topic');
var Message = require('../core/Message');
var EventEmitter2 = require('eventemitter2').EventEmitter2;
/**
* An actionlib action client.
*
* Emits the following events:
* * 'timeout' - if a timeout occurred while sending a goal
* * 'status' - the status messages received from the action server
* * 'feedback' - the feedback messages received from the action server
* * 'result' - the result returned from the action server
*
* @constructor
* @param options - object with following keys:
* * ros - the ROSLIB.Ros connection handle
* * serverName - the action server name, like /fibonacci
* * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction'
* * timeout - the timeout length when connecting to the action server
*/
function ActionClient(options) {
var that = this;
options = options || {};
this.ros = options.ros;
this.serverName = options.serverName;
this.actionName = options.actionName;
this.timeout = options.timeout;
this.omitFeedback = options.omitFeedback;
this.omitStatus = options.omitStatus;
this.omitResult = options.omitResult;
this.goals = {};
// flag to check if a status has been received
var receivedStatus = false;
// create the topics associated with actionlib
var feedbackListener = new Topic({
ros : this.ros,
name : this.serverName + '/feedback',
messageType : this.actionName + 'Feedback'
});
var statusListener = new Topic({
ros : this.ros,
name : this.serverName + '/status',
messageType : 'actionlib_msgs/GoalStatusArray'
});
var resultListener = new Topic({
ros : this.ros,
name : this.serverName + '/result',
messageType : this.actionName + 'Result'
});
this.goalTopic = new Topic({
ros : this.ros,
name : this.serverName + '/goal',
messageType : this.actionName + 'Goal'
});
this.cancelTopic = new Topic({
ros : this.ros,
name : this.serverName + '/cancel',
messageType : 'actionlib_msgs/GoalID'
});
// advertise the goal and cancel topics
this.goalTopic.advertise();
this.cancelTopic.advertise();
// subscribe to the status topic
if (!this.omitStatus) {
statusListener.subscribe(function(statusMessage) {
receivedStatus = true;
statusMessage.status_list.forEach(function(status) {
var goal = that.goals[status.goal_id.id];
if (goal) {
goal.emit('status', status);
}
});
});
}
// subscribe the the feedback topic
if (!this.omitFeedback) {
feedbackListener.subscribe(function(feedbackMessage) {
var goal = that.goals[feedbackMessage.status.goal_id.id];
if (goal) {
goal.emit('status', feedbackMessage.status);
goal.emit('feedback', feedbackMessage.feedback);
}
});
}
// subscribe to the result topic
if (!this.omitResult) {
resultListener.subscribe(function(resultMessage) {
var goal = that.goals[resultMessage.status.goal_id.id];
if (goal) {
goal.emit('status', resultMessage.status);
goal.emit('result', resultMessage.result);
}
});
}
// If timeout specified, emit a 'timeout' event if the action server does not respond
if (this.timeout) {
setTimeout(function() {
if (!receivedStatus) {
that.emit('timeout');
}
}, this.timeout);
}
}
ActionClient.prototype.__proto__ = EventEmitter2.prototype;
/**
* Cancel all goals associated with this ActionClient.
*/
ActionClient.prototype.cancel = function() {
var cancelMessage = new Message();
this.cancelTopic.publish(cancelMessage);
};
module.exports = ActionClient;