Skip to content
This repository was archived by the owner on Dec 8, 2022. It is now read-only.

Commit 9e780b4

Browse files
committed
[map_nav] updated and compiling for indigo.
This updates the api for indigo with the changes discussed in #42.
1 parent c758ade commit 9e780b4

File tree

5 files changed

+75
-79
lines changed

5 files changed

+75
-79
lines changed

Diff for: map_nav/src/main/java/com.github.rosjava.android_apps.map_nav/InitialPoseSubscriberLayer.java

+11-17
Original file line numberDiff line numberDiff line change
@@ -2,25 +2,22 @@
22

33
import javax.microedition.khronos.opengles.GL10;
44

5-
import org.ros.android.view.visualization.Camera;
5+
import org.ros.android.view.visualization.VisualizationView;
66
import org.ros.android.view.visualization.layer.SubscriberLayer;
77
import org.ros.android.view.visualization.layer.TfLayer;
8-
import org.ros.android.view.visualization.shape.RobotShape;
8+
import org.ros.android.view.visualization.shape.GoalShape;
99
import org.ros.android.view.visualization.shape.Shape;
1010
import org.ros.message.MessageListener;
1111
import org.ros.namespace.GraphName;
1212
import org.ros.node.ConnectedNode;
13-
import org.ros.rosjava_geometry.FrameName;
1413
import org.ros.rosjava_geometry.FrameTransform;
15-
import org.ros.rosjava_geometry.FrameTransformTree;
1614
import org.ros.rosjava_geometry.Transform;
1715

18-
import android.os.Handler;
1916

2017
public class InitialPoseSubscriberLayer extends
2118
SubscriberLayer<geometry_msgs.PoseStamped> implements TfLayer {
2219

23-
private final FrameName targetFrame;
20+
private final GraphName targetFrame;
2421

2522
private Shape shape;
2623

@@ -30,27 +27,24 @@ public InitialPoseSubscriberLayer(String topic, String robotFrame) {
3027

3128
public InitialPoseSubscriberLayer(GraphName topic, String robotFrame) {
3229
super(topic, "geometry_msgs/PoseStamped");
33-
targetFrame = FrameName.of(robotFrame);
30+
targetFrame = GraphName.of(robotFrame);
3431
}
3532

3633
@Override
37-
public void draw(GL10 gl) {
38-
shape.draw(gl);
34+
public void draw(VisualizationView view, GL10 gl) {
35+
shape.draw(view, gl);
3936
}
4037

4138
@Override
42-
public void onStart(ConnectedNode connectedNode, Handler handler,
43-
final FrameTransformTree frameTransformTree, Camera camera) {
44-
super.onStart(connectedNode, handler, frameTransformTree, camera);
45-
shape = new RobotShape();
39+
public void onStart(final VisualizationView view, ConnectedNode connectedNode) {
40+
shape = new GoalShape();
4641
getSubscriber().addMessageListener(
4742
new MessageListener<geometry_msgs.PoseStamped>() {
4843
@Override
4944
public void onNewMessage(geometry_msgs.PoseStamped pose) {
50-
FrameName source = FrameName.of(pose.getHeader()
45+
GraphName source = GraphName.of(pose.getHeader()
5146
.getFrameId());
52-
FrameTransform frameTransform = frameTransformTree
53-
.transform(source, targetFrame);
47+
FrameTransform frameTransform = view.getFrameTransformTree().transform(source, targetFrame);
5448
if (frameTransform != null) {
5549
Transform poseTransform = Transform
5650
.fromPoseMessage(pose.getPose());
@@ -62,7 +56,7 @@ public void onNewMessage(geometry_msgs.PoseStamped pose) {
6256
}
6357

6458
@Override
65-
public FrameName getFrame() {
59+
public GraphName getFrame() {
6660
return targetFrame;
6761
}
6862
}

Diff for: map_nav/src/main/java/com.github.rosjava.android_apps.map_nav/MainActivity.java

+26-10
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
import java.util.List;
2222
import java.util.concurrent.TimeUnit;
2323

24+
import com.google.common.collect.Lists;
25+
2426
import android.app.AlertDialog;
2527
import android.app.ProgressDialog;
2628
import android.content.DialogInterface;
@@ -37,6 +39,7 @@
3739

3840
import com.github.rosjava.android_remocons.common_tools.apps.RosAppActivity;
3941
import org.ros.android.view.RosImageView;
42+
import org.ros.android.view.visualization.layer.Layer;
4043
import org.ros.android.view.visualization.layer.RobotLayer;
4144
import org.ros.namespace.NameResolver;
4245
import org.ros.node.NodeConfiguration;
@@ -50,10 +53,11 @@
5053
import org.ros.android.view.visualization.layer.OccupancyGridLayer;
5154
import org.ros.android.view.visualization.layer.LaserScanLayer;
5255
import org.ros.android.view.visualization.layer.PathLayer;
53-
import org.ros.android.view.visualization.layer.PoseSubscriberLayer;
5456
import org.ros.exception.RemoteException;
5557
import org.ros.time.NtpTimeProvider;
5658

59+
import com.github.rosjava.android_apps.map_nav.InitialPoseSubscriberLayer;
60+
5761
/**
5862
* @author [email protected] (Kazuto Murase)
5963
*/
@@ -146,17 +150,20 @@ protected void init(NodeMainExecutor nodeMainExecutor) {
146150

147151
viewControlLayer.addListener(new CameraControlListener() {
148152
@Override
149-
public void onZoom(double focusX, double focusY, double factor) {
153+
public void onZoom(float focusX, float focusY, float factor) {
150154

151155
}
156+
@Override
157+
public void onDoubleTap(float x, float y) {
152158

159+
}
153160
@Override
154161
public void onTranslate(float distanceX, float distanceY) {
155162

156163
}
157164

158165
@Override
159-
public void onRotate(double focusX, double focusY, double deltaAngle) {
166+
public void onRotate(float focusX, float focusY, double deltaAngle) {
160167

161168
}
162169
});
@@ -167,13 +174,22 @@ public void onRotate(double focusX, double focusY, double deltaAngle) {
167174
String initTopic = remaps.get(getString(R.string.initial_pose_topic));
168175
String robotFrame = (String) params.get("robot_frame", getString(R.string.robot_frame));
169176

170-
mapView.addLayer(viewControlLayer);
171-
mapView.addLayer(new OccupancyGridLayer(appNameSpace.resolve(mapTopic).toString()));
172-
mapView.addLayer(new LaserScanLayer(appNameSpace.resolve(scanTopic).toString()));
173-
mapView.addLayer(new PathLayer(appNameSpace.resolve(planTopic).toString()));
174-
mapPosePublisherLayer = new com.github.rosjava.android_apps.map_nav.MapPosePublisherLayer(appNameSpace, this, params, remaps);
175-
mapView.addLayer(mapPosePublisherLayer);
176-
mapView.addLayer(new com.github.rosjava.android_apps.map_nav.InitialPoseSubscriberLayer(appNameSpace.resolve(initTopic).toString(), robotFrame));
177+
OccupancyGridLayer occupancyGridLayer = new OccupancyGridLayer(appNameSpace.resolve(mapTopic).toString());
178+
LaserScanLayer laserScanLayer = new LaserScanLayer(appNameSpace.resolve(scanTopic).toString());
179+
PathLayer pathLayer = new PathLayer(appNameSpace.resolve(planTopic).toString());
180+
mapPosePublisherLayer = new com.github.rosjava.android_apps.map_nav.MapPosePublisherLayer(appNameSpace, params, remaps);
181+
InitialPoseSubscriberLayer initialPoseSubscriberLayer = new InitialPoseSubscriberLayer(appNameSpace.resolve(initTopic).toString(), robotFrame);
182+
183+
mapView.onCreate(
184+
Lists.<Layer>newArrayList(
185+
viewControlLayer,
186+
occupancyGridLayer,
187+
laserScanLayer,
188+
pathLayer,
189+
mapPosePublisherLayer,
190+
initialPoseSubscriberLayer)
191+
);
192+
177193
NtpTimeProvider ntpTimeProvider = new NtpTimeProvider(
178194
InetAddressFactory.newFromHostString("192.168.0.1"),
179195
nodeMainExecutor.getScheduledExecutorService());

Diff for: map_nav/src/main/java/com.github.rosjava.android_apps.map_nav/MapPosePublisherLayer.java

+23-33
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
package com.github.rosjava.android_apps.map_nav;
22

3-
import android.content.Context;
4-
import android.os.Handler;
53
import android.view.GestureDetector;
64
import android.view.MotionEvent;
75

@@ -11,18 +9,15 @@
119

1210
import javax.microedition.khronos.opengles.GL10;
1311

14-
import org.ros.android.view.visualization.Camera;
1512
import org.ros.android.view.visualization.VisualizationView;
1613
import org.ros.android.view.visualization.layer.DefaultLayer;
17-
import org.ros.android.view.visualization.shape.PoseShape;
14+
import org.ros.android.view.visualization.shape.PixelSpacePoseShape;
1815
import org.ros.android.view.visualization.shape.Shape;
1916
import org.ros.namespace.GraphName;
2017
import org.ros.namespace.NameResolver;
2118
import org.ros.node.ConnectedNode;
2219
import org.ros.node.Node;
2320
import org.ros.node.topic.Publisher;
24-
import org.ros.rosjava_geometry.FrameName;
25-
import org.ros.rosjava_geometry.FrameTransformTree;
2621
import org.ros.rosjava_geometry.Transform;
2722
import org.ros.rosjava_geometry.Vector3;
2823

@@ -34,7 +29,6 @@
3429

3530
public class MapPosePublisherLayer extends DefaultLayer {
3631

37-
private final Context context;
3832
private Shape shape;
3933
private Publisher<geometry_msgs.PoseWithCovarianceStamped> initialPosePublisher;
4034
private Publisher<geometry_msgs.PoseStamped> androidGoalPublisher;
@@ -44,7 +38,6 @@ public class MapPosePublisherLayer extends DefaultLayer {
4438
private GestureDetector gestureDetector;
4539
private Transform pose;
4640
private Transform fixedPose;
47-
private Camera camera;
4841
private ConnectedNode connectedNode;
4942
private int mode;
5043
private static final int POSE_MODE = 0;
@@ -56,18 +49,17 @@ public class MapPosePublisherLayer extends DefaultLayer {
5649
private String simpleGoalTopic;
5750
private String moveBaseGoalTopic;
5851

59-
public MapPosePublisherLayer(final NameResolver newNameResolver, final Context context,
52+
public MapPosePublisherLayer(final NameResolver newNameResolver,
6053
final AppParameters params, final AppRemappings remaps) {
6154
this.nameResolver = newNameResolver;
62-
this.context = context;
6355
visible = false;
6456

65-
this.mapFrame = (String) params.get("map_frame", context.getString(R.string.map_frame));
66-
this.robotFrame = (String) params.get("robot_frame", context.getString(R.string.robot_frame));
57+
this.mapFrame = (String) params.get("map_frame", R.string.map_frame);
58+
this.robotFrame = (String) params.get("robot_frame", R.string.robot_frame);
6759

68-
this.initialPoseTopic = remaps.get(context.getString(R.string.initial_pose_topic));
69-
this.simpleGoalTopic = remaps.get(context.getString(R.string.simple_goal_topic));
70-
this.moveBaseGoalTopic = remaps.get(context.getString(R.string.move_base_goal_topic));
60+
this.initialPoseTopic = remaps.get(R.string.initial_pose_topic);
61+
this.simpleGoalTopic = remaps.get(R.string.simple_goal_topic);
62+
this.moveBaseGoalTopic = remaps.get(R.string.move_base_goal_topic);
7163
}
7264

7365
public void setPoseMode() {
@@ -79,10 +71,10 @@ public void setGoalMode() {
7971
}
8072

8173
@Override
82-
public void draw(GL10 gl) {
74+
public void draw(VisualizationView view, GL10 gl) {
8375
if (visible) {
8476
Preconditions.checkNotNull(pose);
85-
shape.draw(gl);
77+
shape.draw(view, gl);
8678
}
8779
}
8880

@@ -102,7 +94,7 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
10294

10395
if (event.getAction() == MotionEvent.ACTION_MOVE) {
10496
poseVector = pose.apply(Vector3.zero());
105-
pointerVector = camera.toMetricCoordinates((int) event.getX(),
97+
pointerVector = view.getCamera().toCameraFrame((int) event.getX(),
10698
(int) event.getY());
10799

108100
double angle = angle(pointerVector.getX(),
@@ -119,18 +111,18 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
119111
PoseStamped poseStamped;
120112
switch (mode) {
121113
case POSE_MODE:
122-
camera.setFrame(mapFrame);
114+
view.getCamera().setFrame(mapFrame);
123115
poseVector = fixedPose.apply(Vector3.zero());
124-
pointerVector = camera.toMetricCoordinates(
116+
pointerVector = view.getCamera().toCameraFrame(
125117
(int) event.getX(), (int) event.getY());
126118
double angle2 = angle(pointerVector.getX(),
127119
pointerVector.getY(), poseVector.getX(),
128120
poseVector.getY());
129121
fixedPose = Transform.translation(poseVector).multiply(
130122
Transform.zRotation(angle2));
131-
camera.setFrame(robotFrame);
123+
view.getCamera().setFrame(robotFrame);
132124
poseStamped = fixedPose.toPoseStampedMessage(
133-
FrameName.of(robotFrame),
125+
GraphName.of(robotFrame),
134126
connectedNode.getCurrentTime(),
135127
androidGoalPublisher.newMessage());
136128

@@ -146,7 +138,7 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
146138
break;
147139
case GOAL_MODE:
148140
poseStamped = pose.toPoseStampedMessage(
149-
FrameName.of(robotFrame),
141+
GraphName.of(robotFrame),
150142
connectedNode.getCurrentTime(),
151143
androidGoalPublisher.newMessage());
152144
androidGoalPublisher.publish(poseStamped);
@@ -169,11 +161,9 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
169161
}
170162

171163
@Override
172-
public void onStart(ConnectedNode connectedNode, Handler handler,
173-
FrameTransformTree frameTransformTree, final Camera camera) {
164+
public void onStart(final VisualizationView view, ConnectedNode connectedNode) {
174165
this.connectedNode = connectedNode;
175-
this.camera = camera;
176-
shape = new PoseShape(camera);
166+
shape = new PixelSpacePoseShape();
177167
mode = POSE_MODE;
178168

179169
initialPosePublisher = connectedNode.newPublisher(nameResolver.resolve(initialPoseTopic).toString(),
@@ -182,20 +172,20 @@ public void onStart(ConnectedNode connectedNode, Handler handler,
182172
"geometry_msgs/PoseStamped");
183173
goalPublisher = connectedNode.newPublisher(nameResolver.resolve(moveBaseGoalTopic).toString(),
184174
"move_base_msgs/MoveBaseActionGoal");
185-
handler.post(new Runnable() {
175+
view.post(new Runnable() {
186176
@Override
187177
public void run() {
188-
gestureDetector = new GestureDetector(context,
178+
gestureDetector = new GestureDetector(view.getContext(),
189179
new GestureDetector.SimpleOnGestureListener() {
190180
@Override
191181
public void onLongPress(MotionEvent e) {
192-
pose = Transform.translation(camera.toMetricCoordinates(
182+
pose = Transform.translation(view.getCamera().toCameraFrame(
193183
(int) e.getX(), (int) e.getY()));
194184
shape.setTransform(pose);
195-
camera.setFrame(mapFrame);
196-
fixedPose = Transform.translation(camera.toMetricCoordinates(
185+
view.getCamera().setFrame(mapFrame);
186+
fixedPose = Transform.translation(view.getCamera().toCameraFrame(
197187
(int) e.getX(), (int) e.getY()));
198-
camera.setFrame(robotFrame);
188+
view.getCamera().setFrame(robotFrame);
199189
visible = true;
200190
}
201191
});

0 commit comments

Comments
 (0)