Go to the documentation of this file.00001 package com.ros.turtlebot.apps.panorama;
00002
00003 import org.ros.address.InetAddressFactory;
00004 import org.ros.android.MessageCallable;
00005 import org.ros.android.robotapp.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 setDefaultRobotName(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("XXXXXXX", "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_panorama.TakePanoRequest, turtlebot_panorama.TakePanoResponse> serviceClient;
00205 try
00206 {
00207 serviceClient = node.newServiceClient("/turtlebot_panorama/take_pano", turtlebot_panorama.TakePano._TYPE);
00208 }
00209 catch (ServiceNotFoundException e)
00210 {
00211 Log.e("PanoramaActivity", "Service not found: " + e.getMessage());
00212 Toast.makeText(getBaseContext(), "Panorama service not found", Toast.LENGTH_LONG).show();
00213 return;
00214 }
00215 final turtlebot_panorama.TakePanoRequest request = serviceClient.newMessage();
00216
00217 SeekBar ang_speed = (SeekBar)findViewById(R.id.seekBar_speed);
00218 SeekBar pano_angle = (SeekBar)findViewById(R.id.seekBar_angle);
00219 SeekBar snap_interv = (SeekBar)findViewById(R.id.seekBar_interval);
00220 CheckBox continuous = (CheckBox)findViewById(R.id.checkBox_continuous);
00221 if (continuous.isChecked() == true)
00222 request.setSnapInterval(snap_interv.getProgress()/100.0f);
00223 else
00224 request.setSnapInterval(snap_interv.getProgress());
00225
00226 request.setRotVel((float)((ang_speed.getProgress()*Math.PI)/180.0));
00227 request.setPanoAngle(pano_angle.getProgress());
00228 request.setMode(mode);
00229
00230 serviceClient.call(request, new ServiceResponseListener<turtlebot_panorama.TakePanoResponse>() {
00231 @Override
00232 public void onSuccess(turtlebot_panorama.TakePanoResponse response) {
00233 Log.i("PanoramaActivity", "Service result: success (status " + response.getStatus() + ")");
00234 node.getLog().info(String.format("Service result %d", response.getStatus()));
00235 if (request.getMode() == turtlebot_panorama.TakePanoRequest.STOP)
00236 showToast("Take panorama stoped");
00237 else
00238 showToast("Take panorama started");
00239 }
00240
00241 @Override
00242 public void onFailure(RemoteException e) {
00243 Log.e("PanoramaActivity", "Service result: failure (" + e.getMessage() + ")");
00244 node.getLog().info(String.format("Service result: failure (%s)", e.getMessage()));
00245 showToast("Take panorama failed");
00246 }
00247 });
00248 }
00249
00250 @Override
00251 public void onStart(ConnectedNode connectedNode)
00252 {
00253 Log.d("PanoramaActivity", connectedNode.getName() + " node started");
00254 node = connectedNode;
00255
00256 NameResolver appNameSpace = getAppNameSpace();
00257 String panoImgTopic = appNameSpace.resolve("/turtlebot_panorama/panorama/compressed").toString();
00258
00259 Subscriber<sensor_msgs.CompressedImage> subscriber =
00260 connectedNode.newSubscriber(panoImgTopic, sensor_msgs.CompressedImage._TYPE);
00261 subscriber.addMessageListener(new MessageListener<sensor_msgs.CompressedImage>() {
00262 @Override
00263 public void onNewMessage(final sensor_msgs.CompressedImage message) {
00264 imgView.post(new Runnable() {
00265 @Override
00266 public void run() {
00267 imgView.setImageBitmap(callable.call(message));
00268 }
00269 });
00270 imgView.postInvalidate();
00271 }
00272 });
00273 }
00274
00275 @Override
00276 public void onError(Node n, Throwable e)
00277 {
00278 Log.e("PanoramaActivity", n.getName() + " node error: " + e.getMessage());
00279 }
00280
00281 @Override
00282 public void onShutdown(Node n)
00283 {
00284 Log.d("PanoramaActivity", n.getName() + " node shuting down...");
00285 }
00286
00287 @Override
00288 public void onShutdownComplete(Node n)
00289 {
00290 Log.d("PanoramaActivity", n.getName() + " node shutdown completed");
00291 }
00292
00293 @Override
00294 public GraphName getDefaultNodeName()
00295 {
00296 return GraphName.of("android/panorama");
00297 }
00298
00299
00300
00301
00302
00303
00304 private final OnClickListener backButtonListener = new OnClickListener()
00305 {
00306 @Override
00307 public void onClick(View v)
00308 {
00309 onBackPressed();
00310 }
00311 };
00312
00313 private final OnClickListener startButtonListener = new OnClickListener()
00314 {
00315 @Override
00316 public void onClick(View v)
00317 {
00318 CheckBox continuous = (CheckBox)findViewById(R.id.checkBox_continuous);
00319
00320 if (continuous.isChecked() == true)
00321 callService(turtlebot_panorama.TakePanoRequest.CONTINUOUS);
00322 else
00323 callService(turtlebot_panorama.TakePanoRequest.SNAPANDROTATE);
00324 }
00325 };
00326
00327 private final OnClickListener stopButtonListener = new OnClickListener()
00328 {
00329 @Override
00330 public void onClick(View v)
00331 {
00332 callService(turtlebot_panorama.TakePanoRequest.STOP);
00333 }
00334 };
00335
00336 private final OnCheckedChangeListener contCheckListener = new OnCheckedChangeListener()
00337 {
00338 @Override
00339 public void onCheckedChanged(CompoundButton cb, boolean checked)
00340 {
00341 SeekBar snap_interv = (SeekBar)findViewById(R.id.seekBar_interval);
00342 if (checked == true)
00343 {
00344
00345 snap_interv.setMax(5000);
00346 snap_interv.setProgress(Math.round((snap_interv.getProgress()*5000)/90));
00347 }
00348 else
00349 {
00350
00351 snap_interv.setProgress(Math.round((snap_interv.getProgress()*90)/5000));
00352 snap_interv.setMax(90);
00353 }
00354 }
00355 };
00356
00357 private final OnSeekBarChangeListener speedBarListener = new OnSeekBarChangeListener()
00358 {
00359 @Override
00360 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00361 {
00362 if (lastToast == null)
00363 lastToast = Toast.makeText(getBaseContext(), progress + " deg/s", Toast.LENGTH_SHORT);
00364 else
00365 lastToast.setText(progress + " deg/s");
00366
00367 lastToast.show();
00368 }
00369
00370 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00371 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00372 };
00373
00374 private final OnSeekBarChangeListener angleBarListener = new OnSeekBarChangeListener()
00375 {
00376 @Override
00377 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00378 {
00379 if (lastToast == null)
00380 lastToast = Toast.makeText(getBaseContext(), progress + " degrees", Toast.LENGTH_SHORT);
00381 else
00382 lastToast.setText(progress + " degrees");
00383
00384 lastToast.show();
00385 }
00386
00387 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00388 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00389 };
00390
00391 private final OnSeekBarChangeListener intervalBarListener = new OnSeekBarChangeListener()
00392 {
00393 @Override
00394 public void onProgressChanged(SeekBar seekBar, int progress, boolean fromUser)
00395 {
00396 if (seekBar.getMax() > 360)
00397 {
00398 if (lastToast == null)
00399 lastToast = Toast.makeText(getBaseContext(), (progress/100)/10.0 + " seconds", Toast.LENGTH_SHORT);
00400 else
00401 lastToast.setText((progress/100)/10.0 + " seconds");
00402 }
00403 else
00404 {
00405 if (lastToast == null)
00406 lastToast = Toast.makeText(getBaseContext(), progress + " degrees", Toast.LENGTH_SHORT);
00407 else
00408 lastToast.setText(progress + " degrees");
00409 }
00410 lastToast.show();
00411 }
00412
00413 @Override public void onStartTrackingTouch(SeekBar seekBar) { }
00414 @Override public void onStopTrackingTouch(SeekBar seekBar) { }
00415 };
00416 }