-
Notifications
You must be signed in to change notification settings - Fork 37
/
nav2d.js
180 lines (162 loc) · 5.29 KB
/
nav2d.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
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
/**
* @author Russell Toris - rctoris@wpi.edu
*/
var NAV2D = NAV2D || {
REVISION : '1'
};
/**
* @author Russell Toris - rctoris@wpi.edu
*/
/**
* A navigator can be used to add click-to-navigate options to an object.
*
* @constructor
* @param options - object with following keys:
* * ros - the ROSLIB.Ros connection handle
* * serverName (optional) - the action server name to use for navigation, like '/move_base'
* * actionName (optional) - the navigation action name, like 'move_base_msgs/MoveBaseAction'
* * rootObject (optional) - the root object to add the click listeners to and render robot markers to
*/
NAV2D.Navigator = function(options) {
var that = this;
options = options || {};
var ros = options.ros;
var serverName = options.serverName || '/move_base';
var actionName = options.actionName || 'move_base_msgs/MoveBaseAction';
this.rootObject = options.rootObject || new createjs.Container();
// setup the actionlib client
var actionClient = new ROSLIB.ActionClient({
ros : ros,
actionName : actionName,
serverName : serverName
});
/**
* Send a goal to the navigation stack with the given pose.
*
* @param pose - the goal pose
*/
function sendGoal(pose) {
// create a goal
var goal = new ROSLIB.Goal({
actionClient : actionClient,
goalMessage : {
target_pose : {
header : {
frame_id : '/map'
},
pose : pose
}
}
});
goal.send();
// create a marker for the goal
var goalMarker = new ROS2D.NavigationArrow({
size : 8,
strokeSize : 1,
fillColor : createjs.Graphics.getRGB(255, 64, 128, 0.66),
pulse : true
});
goalMarker.x = pose.position.x;
goalMarker.y = -pose.position.y;
goalMarker.rotation = stage.rosQuaternionToGlobalTheta(pose.orientation);
goalMarker.scaleX = 1.0 / stage.scaleX;
goalMarker.scaleY = 1.0 / stage.scaleY;
that.rootObject.addChild(goalMarker);
goal.on('result', function() {
that.rootObject.removeChild(goalMarker);
});
}
// get a handle to the stage
var stage;
if (that.rootObject instanceof createjs.Stage) {
stage = that.rootObject;
} else {
stage = that.rootObject.getStage();
}
// marker for the robot
var robotMarker = new ROS2D.NavigationArrow({
size : 12,
strokeSize : 1,
fillColor : createjs.Graphics.getRGB(255, 128, 0, 0.66),
pulse : true
});
// wait for a pose to come in first
robotMarker.visible = false;
this.rootObject.addChild(robotMarker);
var initScaleSet = false;
// setup a listener for the robot pose
var poseListener = new ROSLIB.Topic({
ros : ros,
name : '/robot_pose',
messageType : 'geometry_msgs/Pose',
throttle_rate : 100
});
poseListener.subscribe(function(pose) {
// update the robots position on the map
robotMarker.x = pose.position.x;
robotMarker.y = -pose.position.y;
if (!initScaleSet) {
robotMarker.scaleX = 1.0 / stage.scaleX;
robotMarker.scaleY = 1.0 / stage.scaleY;
initScaleSet = true;
}
// change the angle
robotMarker.rotation = stage.rosQuaternionToGlobalTheta(pose.orientation);
robotMarker.visible = true;
});
// setup a double click listener (no orientation)
this.rootObject.addEventListener('dblclick', function(event) {
// convert to ROS coordinates
var coords = stage.globalToRos(event.stageX, event.stageY);
var pose = new ROSLIB.Pose({
position : new ROSLIB.Vector3(coords)
});
// send the goal
sendGoal(pose);
});
};
/**
* @author Russell Toris - rctoris@wpi.edu
*/
/**
* A OccupancyGridClientNav uses an OccupancyGridClient to create a map for use with a Navigator.
*
* @constructor
* @param options - object with following keys:
* * ros - the ROSLIB.Ros connection handle
* * topic (optional) - the map topic to listen to
* * rootObject (optional) - the root object to add this marker to
* * continuous (optional) - if the map should be continuously loaded (e.g., for SLAM)
* * serverName (optional) - the action server name to use for navigation, like '/move_base'
* * actionName (optional) - the navigation action name, like 'move_base_msgs/MoveBaseAction'
* * rootObject (optional) - the root object to add the click listeners to and render robot markers to
* * viewer - the main viewer to render to
*/
NAV2D.OccupancyGridClientNav = function(options) {
var that = this;
options = options || {};
this.ros = options.ros;
var topic = options.topic || '/map';
var continuous = options.continuous;
this.serverName = options.serverName || '/move_base';
this.actionName = options.actionName || 'move_base_msgs/MoveBaseAction';
this.rootObject = options.rootObject || new createjs.Container();
this.viewer = options.viewer;
this.navigator = null;
// setup a client to get the map
var client = new ROS2D.OccupancyGridClient({
ros : this.ros,
rootObject : this.rootObject,
continuous : continuous
});
client.on('change', function() {
that.navigator = new NAV2D.Navigator({
ros : that.ros,
serverName : that.serverName,
actionName : that.actionName,
rootObject : that.rootObject
});
// scale the viewer to fit the map
that.viewer.scaleToDimensions(client.currentGrid.width, client.currentGrid.height);
});
};