forked from RobotWebTools/roslibjs
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathParam.js
83 lines (71 loc) · 1.72 KB
/
Param.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
/**
* @fileoverview
* @author Brandon Alexander - [email protected]
*/
var Service = require('./Service');
var ServiceRequest = require('./ServiceRequest');
/**
* A ROS parameter.
*
* @constructor
* @param options - possible keys include:
* * ros - the ROSLIB.Ros connection handle
* * name - the param name, like max_vel_x
*/
function Param(options) {
options = options || {};
this.ros = options.ros;
this.name = options.name;
}
/**
* Fetches the value of the param.
*
* @param callback - function with the following params:
* * value - the value of the param from ROS.
*/
Param.prototype.get = function(callback) {
var paramClient = new Service({
ros : this.ros,
name : '/rosapi/get_param',
serviceType : 'rosapi/GetParam'
});
var request = new ServiceRequest({
name : this.name
});
paramClient.callService(request, function(result) {
var value = JSON.parse(result.value);
callback(value);
});
};
/**
* Sets the value of the param in ROS.
*
* @param value - value to set param to.
*/
Param.prototype.set = function(value, callback) {
var paramClient = new Service({
ros : this.ros,
name : '/rosapi/set_param',
serviceType : 'rosapi/SetParam'
});
var request = new ServiceRequest({
name : this.name,
value : JSON.stringify(value)
});
paramClient.callService(request, callback);
};
/**
* Delete this parameter on the ROS server.
*/
Param.prototype.delete = function(callback) {
var paramClient = new Service({
ros : this.ros,
name : '/rosapi/delete_param',
serviceType : 'rosapi/DeleteParam'
});
var request = new ServiceRequest({
name : this.name
});
paramClient.callService(request, callback);
};
module.exports = Param;