1
1
package com .github .rosjava .android_apps .map_nav ;
2
2
3
- import android .content .Context ;
4
- import android .os .Handler ;
5
3
import android .view .GestureDetector ;
6
4
import android .view .MotionEvent ;
7
5
11
9
12
10
import javax .microedition .khronos .opengles .GL10 ;
13
11
14
- import org .ros .android .view .visualization .Camera ;
15
12
import org .ros .android .view .visualization .VisualizationView ;
16
13
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 ;
18
15
import org .ros .android .view .visualization .shape .Shape ;
19
16
import org .ros .namespace .GraphName ;
20
17
import org .ros .namespace .NameResolver ;
21
18
import org .ros .node .ConnectedNode ;
22
19
import org .ros .node .Node ;
23
20
import org .ros .node .topic .Publisher ;
24
- import org .ros .rosjava_geometry .FrameName ;
25
- import org .ros .rosjava_geometry .FrameTransformTree ;
26
21
import org .ros .rosjava_geometry .Transform ;
27
22
import org .ros .rosjava_geometry .Vector3 ;
28
23
34
29
35
30
public class MapPosePublisherLayer extends DefaultLayer {
36
31
37
- private final Context context ;
38
32
private Shape shape ;
39
33
private Publisher <geometry_msgs .PoseWithCovarianceStamped > initialPosePublisher ;
40
34
private Publisher <geometry_msgs .PoseStamped > androidGoalPublisher ;
@@ -44,7 +38,6 @@ public class MapPosePublisherLayer extends DefaultLayer {
44
38
private GestureDetector gestureDetector ;
45
39
private Transform pose ;
46
40
private Transform fixedPose ;
47
- private Camera camera ;
48
41
private ConnectedNode connectedNode ;
49
42
private int mode ;
50
43
private static final int POSE_MODE = 0 ;
@@ -56,18 +49,17 @@ public class MapPosePublisherLayer extends DefaultLayer {
56
49
private String simpleGoalTopic ;
57
50
private String moveBaseGoalTopic ;
58
51
59
- public MapPosePublisherLayer (final NameResolver newNameResolver , final Context context ,
52
+ public MapPosePublisherLayer (final NameResolver newNameResolver ,
60
53
final AppParameters params , final AppRemappings remaps ) {
61
54
this .nameResolver = newNameResolver ;
62
- this .context = context ;
63
55
visible = false ;
64
56
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 );
67
59
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 );
71
63
}
72
64
73
65
public void setPoseMode () {
@@ -79,10 +71,10 @@ public void setGoalMode() {
79
71
}
80
72
81
73
@ Override
82
- public void draw (GL10 gl ) {
74
+ public void draw (VisualizationView view , GL10 gl ) {
83
75
if (visible ) {
84
76
Preconditions .checkNotNull (pose );
85
- shape .draw (gl );
77
+ shape .draw (view , gl );
86
78
}
87
79
}
88
80
@@ -102,7 +94,7 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
102
94
103
95
if (event .getAction () == MotionEvent .ACTION_MOVE ) {
104
96
poseVector = pose .apply (Vector3 .zero ());
105
- pointerVector = camera . toMetricCoordinates ((int ) event .getX (),
97
+ pointerVector = view . getCamera (). toCameraFrame ((int ) event .getX (),
106
98
(int ) event .getY ());
107
99
108
100
double angle = angle (pointerVector .getX (),
@@ -119,18 +111,18 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
119
111
PoseStamped poseStamped ;
120
112
switch (mode ) {
121
113
case POSE_MODE :
122
- camera .setFrame (mapFrame );
114
+ view . getCamera () .setFrame (mapFrame );
123
115
poseVector = fixedPose .apply (Vector3 .zero ());
124
- pointerVector = camera . toMetricCoordinates (
116
+ pointerVector = view . getCamera (). toCameraFrame (
125
117
(int ) event .getX (), (int ) event .getY ());
126
118
double angle2 = angle (pointerVector .getX (),
127
119
pointerVector .getY (), poseVector .getX (),
128
120
poseVector .getY ());
129
121
fixedPose = Transform .translation (poseVector ).multiply (
130
122
Transform .zRotation (angle2 ));
131
- camera .setFrame (robotFrame );
123
+ view . getCamera () .setFrame (robotFrame );
132
124
poseStamped = fixedPose .toPoseStampedMessage (
133
- FrameName .of (robotFrame ),
125
+ GraphName .of (robotFrame ),
134
126
connectedNode .getCurrentTime (),
135
127
androidGoalPublisher .newMessage ());
136
128
@@ -146,7 +138,7 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
146
138
break ;
147
139
case GOAL_MODE :
148
140
poseStamped = pose .toPoseStampedMessage (
149
- FrameName .of (robotFrame ),
141
+ GraphName .of (robotFrame ),
150
142
connectedNode .getCurrentTime (),
151
143
androidGoalPublisher .newMessage ());
152
144
androidGoalPublisher .publish (poseStamped );
@@ -169,11 +161,9 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
169
161
}
170
162
171
163
@ Override
172
- public void onStart (ConnectedNode connectedNode , Handler handler ,
173
- FrameTransformTree frameTransformTree , final Camera camera ) {
164
+ public void onStart (final VisualizationView view , ConnectedNode connectedNode ) {
174
165
this .connectedNode = connectedNode ;
175
- this .camera = camera ;
176
- shape = new PoseShape (camera );
166
+ shape = new PixelSpacePoseShape ();
177
167
mode = POSE_MODE ;
178
168
179
169
initialPosePublisher = connectedNode .newPublisher (nameResolver .resolve (initialPoseTopic ).toString (),
@@ -182,20 +172,20 @@ public void onStart(ConnectedNode connectedNode, Handler handler,
182
172
"geometry_msgs/PoseStamped" );
183
173
goalPublisher = connectedNode .newPublisher (nameResolver .resolve (moveBaseGoalTopic ).toString (),
184
174
"move_base_msgs/MoveBaseActionGoal" );
185
- handler .post (new Runnable () {
175
+ view .post (new Runnable () {
186
176
@ Override
187
177
public void run () {
188
- gestureDetector = new GestureDetector (context ,
178
+ gestureDetector = new GestureDetector (view . getContext () ,
189
179
new GestureDetector .SimpleOnGestureListener () {
190
180
@ Override
191
181
public void onLongPress (MotionEvent e ) {
192
- pose = Transform .translation (camera . toMetricCoordinates (
182
+ pose = Transform .translation (view . getCamera (). toCameraFrame (
193
183
(int ) e .getX (), (int ) e .getY ()));
194
184
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 (
197
187
(int ) e .getX (), (int ) e .getY ()));
198
- camera .setFrame (robotFrame );
188
+ view . getCamera () .setFrame (robotFrame );
199
189
visible = true ;
200
190
}
201
191
});
0 commit comments