Skip to content

Commit

Permalink
Merge pull request #24 from rctoris/devel
Browse files Browse the repository at this point in the history
shift now added to grid client to center on map
  • Loading branch information
rctoris committed Apr 30, 2013
2 parents 4196ceb + c685965 commit ac73c46
Show file tree
Hide file tree
Showing 6 changed files with 86 additions and 7 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
DEVEL - **r2**
* Shift added to grid client to center on map [(rctoris)](https://github.com/rctoris/)
* OccupancyGridClientNav now correctly uses the topic parameter [(rctoris)](https://github.com/rctoris/)

2013-04-15 - **r1**
* Initial development of NAV2D [(rctoris)](https://github.com/rctoris/)
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ nav2djs depends on:

[EaselJS](https://github.com/CreateJS/EaselJS/). The current supported version is 0.6.0. The current supported version can be found [in this project](include/EaselJS/easeljs.js) or on the Robot Web Tools CDN: ([full](http://cdn.robotwebtools.org/EaselJS/0.6.0/easeljs.js)) | ([min](http://cdn.robotwebtools.org/EaselJS/0.6.0/easeljs.min.js))

[ros2djs](https://github.com/RobotWebTools/ros2djs). The current supported version is r1. The current supported version can be found [in this project](include/ros2djs/ros2d.js) or on the Robot Web Tools CDN: ([full](http://cdn.robotwebtools.org/ros2djs/r1/ros2d.js)) | ([min](http://cdn.robotwebtools.org/ros2djs/r1/ros2d.min.js))
[ros2djs](https://github.com/RobotWebTools/ros2djs). The current supported version is r2. The current supported version can be found [in this project](include/ros2djs/ros2d.js) or on the Robot Web Tools CDN: ([full](http://cdn.robotwebtools.org/ros2djs/r2/ros2d.js)) | ([min](http://cdn.robotwebtools.org/ros2djs/r2/ros2d.min.js))

### Build
Checkout [utils/README.md](utils/README.md) for details on building.
Expand Down
4 changes: 3 additions & 1 deletion build/nav2d.js
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,8 @@ NAV2D.OccupancyGridClientNav = function(options) {
var client = new ROS2D.OccupancyGridClient({
ros : this.ros,
rootObject : this.rootObject,
continuous : continuous
continuous : continuous,
topic : topic
});
client.on('change', function() {
that.navigator = new NAV2D.Navigator({
Expand All @@ -175,6 +176,7 @@ NAV2D.OccupancyGridClientNav = function(options) {
});

// scale the viewer to fit the map
that.viewer.shift(client.currentGrid.pose.position.x, client.currentGrid.pose.position.y);
that.viewer.scaleToDimensions(client.currentGrid.width, client.currentGrid.height);
});
};
2 changes: 1 addition & 1 deletion build/nav2d.min.js

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

79 changes: 76 additions & 3 deletions include/ros2djs/ros2d.js
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,12 @@
*/

var ROS2D = ROS2D || {
REVISION : '1'
REVISION : '2-devel'
};

// convert the given global Stage coordinates to ROS coordinates
createjs.Stage.prototype.globalToRos = function(x, y) {
var rosX = x / this.scaleX;
// change Y direction
var rosX = (x - this.x) / this.scaleX;
var rosY = (this.y - y) / this.scaleY;
return {
x : rosX,
Expand Down Expand Up @@ -102,10 +101,16 @@ ROS2D.OccupancyGrid = function(options) {
createjs.Bitmap.call(this, canvas);
// change Y direction
this.y = -this.height * message.info.resolution;

// scale the image
this.scaleX = message.info.resolution;
this.scaleY = message.info.resolution;
this.width *= this.scaleX;
this.height *= this.scaleY;

// set the pose
this.x += this.pose.position.x;
this.y -= this.pose.position.y;
};
ROS2D.OccupancyGrid.prototype.__proto__ = createjs.Bitmap.prototype;

Expand Down Expand Up @@ -165,6 +170,57 @@ ROS2D.OccupancyGridClient = function(options) {
};
ROS2D.OccupancyGridClient.prototype.__proto__ = EventEmitter2.prototype;

/**
* @author Jihoon Lee- jihoonlee.in@gmail.com
* @author Russell Toris - rctoris@wpi.edu
*/

/**
* A static map that receives from map_server.
*
* Emits the following events:
* * 'change' - there was an update or change in the map
*
* @constructor
* @param options - object with following keys:
* * ros - the ROSLIB.Ros connection handle
* * service (optional) - the map topic to listen to, like '/static_map'
* * rootObject (optional) - the root object to add this marker to
*/
ROS2D.OccupancyGridSrvClient = function(options) {
var that = this;
options = options || {};
var ros = options.ros;
var service = options.service || '/static_map';
this.rootObject = options.rootObject || new createjs.Container();

// current grid that is displayed
this.currentGrid = null;

// Setting up to the service
var rosService = new ROSLIB.Service({
ros : ros,
name : service,
serviceType : 'nav_msgs/GetMap',
compression : 'png'
});

rosService.callService(new ROSLIB.ServiceRequest(),function(response) {
// check for an old map
if (that.currentGrid) {
that.rootObject.removeChild(that.currentGrid);
}

that.currentGrid = new ROS2D.OccupancyGrid({
message : response.map
});
that.rootObject.addChild(that.currentGrid);

that.emit('change', that.currentGrid);
});
};
ROS2D.OccupancyGridSrvClient.prototype.__proto__ = EventEmitter2.prototype;

/**
* @author Russell Toris - rctoris@wpi.edu
*/
Expand Down Expand Up @@ -286,6 +342,23 @@ ROS2D.Viewer.prototype.addObject = function(object) {
* @param height - the height to scale to in meters
*/
ROS2D.Viewer.prototype.scaleToDimensions = function(width, height) {
// store the actual offset in the ROS coordinate system
var tmpY = this.height - (this.scene.y * this.scene.scaleY);
this.scene.scaleX = this.width / width;
this.scene.scaleY = this.height / height;
// reset the offset
this.scene.x = (this.scene.x * this.scene.scaleX);
this.scene.y -= (tmpY * this.scene.scaleY) - tmpY;
};

/**
* Shift the main view of the canvas by the given amount. This is based on the
* ROS coordinate system. That is, Y is opposite that of a traditional canvas.
*
* @param x - the amount to shift by in the x direction in meters
* @param y - the amount to shift by in the y direction in meters
*/
ROS2D.Viewer.prototype.shift = function(x, y) {
this.scene.x -= (x * this.scene.scaleX);
this.scene.y += (y * this.scene.scaleY);
};
4 changes: 3 additions & 1 deletion src/navigator/OccupancyGridClientNav.js
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ NAV2D.OccupancyGridClientNav = function(options) {
var client = new ROS2D.OccupancyGridClient({
ros : this.ros,
rootObject : this.rootObject,
continuous : continuous
continuous : continuous,
topic : topic
});
client.on('change', function() {
that.navigator = new NAV2D.Navigator({
Expand All @@ -44,6 +45,7 @@ NAV2D.OccupancyGridClientNav = function(options) {
});

// scale the viewer to fit the map
that.viewer.shift(client.currentGrid.pose.position.x, client.currentGrid.pose.position.y);
that.viewer.scaleToDimensions(client.currentGrid.width, client.currentGrid.height);
});
};

0 comments on commit ac73c46

Please sign in to comment.