Go to the documentation of this file.00001 package com.github.turtlebot.turtlebot_android.panorama;
00002
00003 import org.ros.address.InetAddressFactory;
00004 import org.ros.android.MessageCallable;
00005 import com.github.rosjava.android_apps.application_management.RosAppActivity;
00006 import org.ros.exception.RemoteException;
00007 import org.ros.exception.ServiceNotFoundException;
00008 import org.ros.message.MessageListener;
00009 import org.ros.namespace.GraphName;
00010 import org.ros.namespace.NameResolver;
00011 import org.ros.node.ConnectedNode;
00012 import org.ros.node.Node;
00013 import org.ros.node.NodeConfiguration;
00014 import org.ros.node.NodeMain;
00015 import org.ros.node.NodeMainExecutor;
00016 import org.ros.node.service.ServiceClient;
00017 import org.ros.node.service.ServiceResponseListener;
00018 import org.ros.node.topic.Subscriber;
00019
00020 import android.content.res.Configuration;
00021 import android.graphics.Bitmap;
00022 import android.graphics.drawable.Drawable;
00023 import android.os.Bundle;
00024 import android.os.StrictMode;
00025 import android.util.Log;
00026 import android.view.View;
00027 import android.view.View.OnClickListener;
00028 import android.widget.Button;
00029 import android.widget.CheckBox;
00030 import android.widget.CompoundButton;
00031 import android.widget.CompoundButton.OnCheckedChangeListener;
00032 import android.widget.ImageView;
00033 import android.widget.SeekBar;
00034 import android.widget.SeekBar.OnSeekBarChangeListener;
00035 import android.widget.Toast;
00036
00037
00038 public class PanoramaActivity extends RosAppActivity implements NodeMain
00039 {
00040 private ImageView imgView;
00041 private Toast lastToast;
00042 private ConnectedNode node;
00043 private final MessageCallable<Bitmap, sensor_msgs.CompressedImage> callable =
00044 new ScaledBitmapFromCompressedImage(2);
00045
00046
00047 public PanoramaActivity()
00048 {
00049 super("PanoramaActivity", "PanoramaActivity");
00050 }
00051
00052
00053
00054
00055
00056
00058 @Override
00059 public void onCreate(Bundle savedInstanceState)
00060 {
00061 setDefaultMasterName(getString(R.string.default_robot));
00062 setDefaultAppName(getString(R.string.default_app));
00063 setDashboardResource(R.id.top_bar);
00064 setMainWindowResource(R.layout.main);
00065
00066 super.onCreate(savedInstanceState);
00067 buildView(false);
00068
00069
00070 if (android.os.Build.VERSION.SDK_INT > 9) {
00071 StrictMode.ThreadPolicy policy = new StrictMode.ThreadPolicy.Builder().permitAll().build();
00072 StrictMode.setThreadPolicy(policy);
00073 }
00074 }
00075
00076 @Override
00077 protected void onStop()
00078 {
00079 super.onStop();
00080 }
00081
00082 @Override
00083 protected void onRestart()
00084 {
00085 super.onRestart();
00086 }
00087
00088 @Override
00089 protected void onPause()
00090 {
00091 super.onPause();
00092 }
00093
00094 @Override
00095 protected void onResume()
00096 {
00097 super.onResume();
00098 }
00099
00100 @Override
00101 public void onConfigurationChanged(Configuration newConfig)
00102 {
00103
00104 Log.e("PanoramaActivity", "onConfigurationChanged");
00105 super.onConfigurationChanged(newConfig);
00106
00107 buildView(true);
00108 }
00109
00110 private void buildView(boolean rebuild)
00111 {
00112 CheckBox prevContCheck = null;
00113 SeekBar prevSpeedBar = null;
00114 SeekBar prevAngleBar = null;
00115 SeekBar prevIntervBar = null;
00116 Drawable prevDrawable = null;
00117
00118 if (rebuild == true)
00119 {
00120
00121
00122 prevContCheck = (CheckBox)findViewById(R.id.checkBox_continuous);
00123 prevSpeedBar = (SeekBar)findViewById(R.id.seekBar_speed);
00124 prevAngleBar = (SeekBar)findViewById(R.id.seekBar_angle);
00125 prevIntervBar = (SeekBar)findViewById(R.id.seekBar_interval);
00126 prevDrawable = imgView.getDrawable();
00127 }
00128
00129
00130 Button backButton = (Button) findViewById(R.id.back_button);
00131 backButton.setOnClickListener(backButtonListener);
00132
00133 Button startButton = (Button)findViewById(R.id.button_start);
00134 startButton.setOnClickListener(startButtonListener);
00135
00136 Button stopButton = (Button)findViewById(R.id.button_stop);
00137 stopButton.setOnClickListener(stopButtonListener);
00138
00139 CheckBox contCheck = (CheckBox)findViewById(R.id.checkBox_continuous);
00140 contCheck.setOnCheckedChangeListener(contCheckListener);
00141 if (rebuild == true)
00142 contCheck.setChecked(prevContCheck.isChecked());
00143
00144 SeekBar speedBar = (SeekBar)findViewById(R.id.seekBar_speed);
00145 speedBar.setOnSeekBarChangeListener(speedBarListener);
00146 if (rebuild == true)
00147 speedBar.setProgress(prevSpeedBar.getProgress());
00148
00149 SeekBar angleBar = (SeekBar)findViewById(R.id.seekBar_angle);
00150 angleBar.setOnSeekBarChangeListener(angleBarListener);
00151 if (rebuild == true)
00152 angleBar.setProgress(prevAngleBar.getProgress());
00153
00154 SeekBar intervBar = (SeekBar)findViewById(R.id.seekBar_interval);
00155 intervBar.setOnSeekBarChangeListener(intervalBarListener);
00156 if (rebuild == true)
00157 intervBar.setProgress(prevIntervBar.getProgress());
00158
00159
00160 imgView = (ImageView)findViewById(R.id.imageView_panorama);
00161 if (rebuild == true)
00162 imgView.setImageDrawable(prevDrawable);
00163 }
00164
00169 public void showToast(final String message)
00170 {
00171 runOnUiThread(new Runnable()
00172 {
00173 @Override
00174 public void run() {
00175 Toast.makeText(getBaseContext(), message, Toast.LENGTH_LONG).show();
00176 }
00177 });
00178 }
00179
00180
00181
00182
00183
00184
00185 @Override
00186 protected void init(NodeMainExecutor nodeMainExecutor)
00187 {
00188 super.init(nodeMainExecutor);
00189
00190 NodeConfiguration nodeConfiguration =
00191 NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress(), getMasterUri());
00192
00193 nodeMainExecutor.execute(this, nodeConfiguration.setNodeName("android/video_view"));
00194 }
00195
00196 protected void callService(byte mode)
00197 {
00198 if (node == null)
00199 {
00200 Log.e("PanoramaActivity", "Still doesn't have a connected node");
00201 return;
00202 }
00203
00204 ServiceClient<turtlebot_msgs.TakePanoramaRequest, turtlebot_msgs.TakePanoramaResponse> serviceClient;
00205 try
00206 {
00207 NameResolver appNameSpace = getMasterNameSpace();
00208 String srvTopic = appNameSpace.resolve("turtlebot_panorama/take_pano").toString();
00209 serviceClient = node.newServiceClient(srvTopic, turtlebot_msgs.TakePanorama._TYPE);
00210 }
00211 catch (ServiceNotFoundException e)
00212 {
00213 Log.e("PanoramaActivity", "Service not found: " + e.getMessage());
00214 Toast.makeText(getBaseContext(), "Panorama service not found", Toast.LENGTH_LONG).show();
00215 return;
00216 }
00217 final turtlebot_msgs.TakePanoramaRequest request = serviceClient.newMessage();
00218
00219 SeekBar ang_speed = (SeekBar)findViewById(R.id.seekBar_speed);
00220 SeekBar pano_angle = (SeekBar)findViewById(R.id.seekBar_angle);
00221 SeekBar snap_interv = (SeekBar)findViewById(R.id.seekBar_interval);
00222 CheckBox continuous = (CheckBox)findViewById(R.id.checkBox_continuous);
00223 if (continuous.isChecked() == true)
00224 request.setSnapInterval(snap_interv.getProgress()/100.0f);
00225 else
00226 request.setSnapInterval(snap_interv.getProgress());
00227
00228 request.setRotVel((float)((ang_speed.getProgress()*Math.PI)/180.0));
00229 request.setPanoAngle(pano_angle.getProgress());
00230 request.setMode(mode);
00231
00232 serviceClient.call(request, new ServiceResponseListener<turtlebot_msgs.TakePanoramaResponse>() {
00233 @Override
00234 public void onSuccess(turtlebot_msgs.TakePanoramaResponse response) {
00235 Log.i("PanoramaActivity", "Service result: success (status " + response.getStatus() + ")");
00236 node.getLog().info(String.format("Service result %d", response.getStatus()));
00237 if (request.getMode() == turtlebot_msgs.TakePanoramaRequest.STOP)
00238 showToast("Take panorama stopped.");
00239 else
00240 showToast("Take panorama started.");
00241 }
00242
00243 @Override
00244 public void onFailure(RemoteException e) {
00245 Log.e("PanoramaActivity", "Service result: failure (" + e.getMessage() + ")");
00246 node.getLog().info(String.format("Service result: failure (%s)", e.getMessage()));
00247 showToast("Take panorama failed");
00248 }
00249 });
00250 }
00251
00252 @Override
00253 public void onStart(ConnectedNode connectedNode)
00254 {
00255 Log.d("PanoramaActivity", connectedNode.getName() + " node started");
00256 node = connectedNode;
00257
00258 NameResolver appNameSpace = getMasterNameSpace();
00259 String panoImgTopic = appNameSpace.resolve("turtlebot_panorama/panorama/compressed").toString();
00260
00261 Subscriber<sensor_msgs.CompressedImage> subscriber =
00262 connectedNode.newSubscriber(panoImgTopic, sensor_msgs.CompressedImage._TYPE);
00263 subscriber.addMessageListener(new MessageListener<sensor_msgs.CompressedImage>() {
00264 @Override
00265 public void onNewMessage(final sensor_msgs.CompressedImage message) {
00266 imgView.post(new Runnable() {
00267 @Override
00268 public void run() {
00269 imgView.setImageBitmap(callable.call(message));
00270 }
00271 });
00272 imgView.postInvalidate();
00273 }
00274 });
00275 }
00276
00277 @Override
00278 public void onError(Node n, Throwable e)
00279 {
00280 Log.e("PanoramaActivity", n.getName() + " node error: " + e.getMessage());
00281 }
00282
00283 @Override
00284 public void onShutdown(Node n)
00285 {
00286 Log.d("PanoramaActivity", n.getName() + " node shuting down...");
00287 }
00288
00289 @Override
00290 public void onShutdownComplete(Node n)
00291 {
00292 Log.d("PanoramaActivity", n.getName() + " node shutdown completed");
00293 }
00294
00295 @Override
00296 public GraphName getDefaultNodeName()
00297 {
00298 return GraphName.of("android/panorama");
00299 }
00300
00301
00302
00303
00304
00305
00306 private final OnClickListener backButtonListener = new OnClickListener()
00307 {
00308 @Override
00309 public void onClick(View v)
00310 {
00311 onBackPressed();
00312 }
00313 };
00314
00315 private final OnClickListener startButtonListener = new OnClickListener()
00316 {
00317 @Override
00318 public void onClick(View v)
00319 {
00320 CheckBox continuous = (CheckBox)findViewById(R.id.checkBox_continuous);
00321
00322 if (continuous.isChecked() == true)
00323 callService(turtlebot_msgs.TakePanoramaRequest.CONTINUOUS);
00324 else
00325 callService(turtlebot_msgs.TakePanoramaRequest.SNAPANDROTATE);
00326 }
00327 };
00328
00329 private final OnClickListener stopButtonListener = new OnClickListener()
00330 {
00331 @Override
00332 public void onClick(View v)
00333 {
00334 callService(turtlebot_msgs.TakePanoramaRequest.STOP);
00335 }
00336 };
00337
00338 private final OnCheckedChangeListener contCheckListener = new OnCheckedChangeListener()
00339 {
00340 @Override
00341 public void onCheckedChanged(CompoundButton cb, boolean checked)
00342 {
00343 SeekBar snap_interv = (SeekBar)findViewById(R.id.seekBar_interval);
00344 if (checked == true)
00345 {
00346
00347 snap_interv.setMax(5000);
00348 snap_interv.setProgress(Math.round((snap_interv.getProgress()*5000)/90));
00349 }
00350 else
00351 {
00352
00353 snap_interv.setProgress(Math.round((snap_interv.getProgress()*90)/5000));
00354 snap_interv.setMax(90);
00355 }
00356 }
00357 };
00358
00359 private final OnSeekBarChangeListener speedBarListener = new OnSeekBarChangeListener()
00360 {
00361 @Override
00362 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00363 {
00364 if (lastToast == null)
00365 lastToast = Toast.makeText(getBaseContext(), progress + " deg/s", Toast.LENGTH_SHORT);
00366 else
00367 lastToast.setText(progress + " deg/s");
00368
00369 lastToast.show();
00370 }
00371
00372 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00373 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00374 };
00375
00376 private final OnSeekBarChangeListener angleBarListener = new OnSeekBarChangeListener()
00377 {
00378 @Override
00379 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00380 {
00381 if (lastToast == null)
00382 lastToast = Toast.makeText(getBaseContext(), progress + " degrees", Toast.LENGTH_SHORT);
00383 else
00384 lastToast.setText(progress + " degrees");
00385
00386 lastToast.show();
00387 }
00388
00389 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00390 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00391 };
00392
00393 private final OnSeekBarChangeListener intervalBarListener = new OnSeekBarChangeListener()
00394 {
00395 @Override
00396 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00397 {
00398 if (seekBar.getMax() > 360)
00399 {
00400 if (lastToast == null)
00401 lastToast = Toast.makeText(getBaseContext(), (progress/100)/10.0 + " seconds", Toast.LENGTH_SHORT);
00402 else
00403 lastToast.setText((progress/100)/10.0 + " seconds");
00404 }
00405 else
00406 {
00407 if (lastToast == null)
00408 lastToast = Toast.makeText(getBaseContext(), progress + " degrees", Toast.LENGTH_SHORT);
00409 else
00410 lastToast.setText(progress + " degrees");
00411 }
00412 lastToast.show();
00413 }
00414
00415 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00416 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00417 };
00418 }