diff --git a/android_core_components/res/layout/master_chooser.xml b/android_core_components/res/layout/master_chooser.xml
index 0e60f8e..cd91c55 100644
--- a/android_core_components/res/layout/master_chooser.xml
+++ b/android_core_components/res/layout/master_chooser.xml
@@ -62,6 +62,7 @@
android:onClick="advancedCheckboxClicked"
android:text="@string/show_advanced"/>
+
-
+
ROS for Android
Connect
Cancel
+ Reset Prefix
Read QRCode
http://localhost:11311/
New Public Master
diff --git a/android_core_components/src/main/java/org/ros/android/MasterChooser.java b/android_core_components/src/main/java/org/ros/android/MasterChooser.java
index b2fc0dc..782411b 100644
--- a/android_core_components/src/main/java/org/ros/android/MasterChooser.java
+++ b/android_core_components/src/main/java/org/ros/android/MasterChooser.java
@@ -30,6 +30,7 @@ import android.os.Bundle;
import android.support.v7.app.AppCompatActivity;
import android.text.Editable;
import android.text.TextWatcher;
+import android.util.Log;
import android.view.View;
import android.widget.AutoCompleteTextView;
import android.widget.Button;
@@ -55,6 +56,7 @@ import java.util.Collections;
import java.util.HashMap;
import java.util.List;
import java.util.Locale;
+import java.util.Random;
import java.util.Set;
import java.util.regex.Pattern;
@@ -116,6 +118,8 @@ public class MasterChooser extends AppCompatActivity {
*/
private static final int RECENT_MASTER_HISTORY_COUNT = 5;
+ private static boolean resetNodePrefix = false;
+
private String selectedInterface;
private AutoCompleteTextView uriText;
private Button connectButton;
@@ -343,6 +347,14 @@ public class MasterChooser extends AppCompatActivity {
}
}
+ public void resetNodePrefixButtonClicked(View unused) {
+ resetNodePrefix = true;
+ }
+
+ public static boolean getResetNodePrefixButtonClicked(){
+ return resetNodePrefix;
+ }
+
public void advancedCheckboxClicked(View view) {
boolean checked = ((CheckBox) view).isChecked();
LinearLayout advancedOptions = (LinearLayout) findViewById(R.id.advancedOptions);
diff --git a/android_core_components/src/main/java/org/ros/android/view/camera/CameraPreviewView.java b/android_core_components/src/main/java/org/ros/android/view/camera/CameraPreviewView.java
index 6944cd9..4cceb87 100644
--- a/android_core_components/src/main/java/org/ros/android/view/camera/CameraPreviewView.java
+++ b/android_core_components/src/main/java/org/ros/android/view/camera/CameraPreviewView.java
@@ -18,16 +18,11 @@ package org.ros.android.view.camera;
import com.google.common.base.Preconditions;
-import android.content.Context;
import android.graphics.ImageFormat;
+import android.graphics.SurfaceTexture;
import android.hardware.Camera;
import android.hardware.Camera.PreviewCallback;
import android.hardware.Camera.Size;
-import android.util.AttributeSet;
-import android.view.SurfaceHolder;
-import android.view.SurfaceView;
-import android.view.View;
-import android.view.ViewGroup;
import org.ros.exception.RosRuntimeException;
import java.io.IOException;
@@ -38,17 +33,22 @@ import java.util.List;
*
* @author damonkohler@google.com (Damon Kohler)
*/
-public class CameraPreviewView extends ViewGroup {
+public class CameraPreviewView {
private final static double ASPECT_TOLERANCE = 0.1;
- private SurfaceHolder surfaceHolder;
+ private SurfaceTexture surfaceTexture;
private Camera camera;
private Size previewSize;
private byte[] previewBuffer;
private RawImageListener rawImageListener;
private BufferingPreviewCallback bufferingPreviewCallback;
+ public CameraPreviewView() {
+ surfaceTexture = new SurfaceTexture(10);
+ bufferingPreviewCallback = new BufferingPreviewCallback();
+ }
+
private final class BufferingPreviewCallback implements PreviewCallback {
@Override
public void onPreviewFrame(byte[] data, Camera camera) {
@@ -61,52 +61,6 @@ public class CameraPreviewView extends ViewGroup {
}
}
- private final class SurfaceHolderCallback implements SurfaceHolder.Callback {
- @Override
- public void surfaceChanged(SurfaceHolder holder, int format, int width, int height) {
- }
-
- @Override
- public void surfaceCreated(SurfaceHolder holder) {
- try {
- if (camera != null) {
- camera.setPreviewDisplay(holder);
- }
- } catch (IOException e) {
- throw new RosRuntimeException(e);
- }
- }
-
- @Override
- public void surfaceDestroyed(SurfaceHolder holder) {
- releaseCamera();
- }
- }
-
- private void init(Context context) {
- SurfaceView surfaceView = new SurfaceView(context);
- addView(surfaceView);
- surfaceHolder = surfaceView.getHolder();
- surfaceHolder.addCallback(new SurfaceHolderCallback());
- surfaceHolder.setType(SurfaceHolder.SURFACE_TYPE_PUSH_BUFFERS);
- bufferingPreviewCallback = new BufferingPreviewCallback();
- }
-
- public CameraPreviewView(Context context) {
- super(context);
- init(context);
- }
-
- public CameraPreviewView(Context context, AttributeSet attrs) {
- super(context, attrs);
- init(context);
- }
-
- public CameraPreviewView(Context context, AttributeSet attrs, int defStyle) {
- super(context, attrs, defStyle);
- init(context);
- }
-
public void releaseCamera() {
if (camera == null) {
return;
@@ -133,7 +87,7 @@ public class CameraPreviewView extends ViewGroup {
camera.startPreview();
try {
// This may have no effect if the SurfaceHolder is not yet created.
- camera.setPreviewDisplay(surfaceHolder);
+ camera.setPreviewTexture(surfaceTexture);
} catch (IOException e) {
throw new RosRuntimeException(e);
}
@@ -142,7 +96,7 @@ public class CameraPreviewView extends ViewGroup {
private void setupCameraParameters() {
Camera.Parameters parameters = camera.getParameters();
List supportedPreviewSizes = parameters.getSupportedPreviewSizes();
- previewSize = getOptimalPreviewSize(supportedPreviewSizes, getWidth(), getHeight());
+ previewSize = getOptimalPreviewSize(supportedPreviewSizes, 1920, 1080);
parameters.setPreviewSize(previewSize.width, previewSize.height);
parameters.setPreviewFormat(ImageFormat.NV21);
camera.setParameters(parameters);
@@ -188,29 +142,4 @@ public class CameraPreviewView extends ViewGroup {
camera.addCallbackBuffer(previewBuffer);
camera.setPreviewCallbackWithBuffer(bufferingPreviewCallback);
}
-
- @Override
- protected void onLayout(boolean changed, int l, int t, int r, int b) {
- if (changed && getChildCount() > 0) {
- final View child = getChildAt(0);
- final int width = r - l;
- final int height = b - t;
-
- int previewWidth = width;
- int previewHeight = height;
- if (previewSize != null) {
- previewWidth = previewSize.width;
- previewHeight = previewSize.height;
- }
-
- // Center the child SurfaceView within the parent.
- if (width * previewHeight > height * previewWidth) {
- final int scaledChildWidth = previewWidth * height / previewHeight;
- child.layout((width - scaledChildWidth) / 2, 0, (width + scaledChildWidth) / 2, height);
- } else {
- final int scaledChildHeight = previewHeight * width / previewWidth;
- child.layout(0, (height - scaledChildHeight) / 2, width, (height + scaledChildHeight) / 2);
- }
- }
- }
}
diff --git a/android_core_components/src/main/java/org/ros/android/view/camera/CompressedImagePublisher.java b/android_core_components/src/main/java/org/ros/android/view/camera/CompressedImagePublisher.java
index 292fcb9..cd59a65 100644
--- a/android_core_components/src/main/java/org/ros/android/view/camera/CompressedImagePublisher.java
+++ b/android_core_components/src/main/java/org/ros/android/view/camera/CompressedImagePublisher.java
@@ -62,13 +62,16 @@ class CompressedImagePublisher implements RawImageListener {
private Rect rect;
private ChannelBufferOutputStream stream;
- public CompressedImagePublisher(ConnectedNode connectedNode) {
+ private static String sID;
+
+ public CompressedImagePublisher(ConnectedNode connectedNode, String nodeID) {
+ sID = nodeID;
this.connectedNode = connectedNode;
this.loadStatus = false;
this.yamlFile = "camera.yaml";
this.lastTime = connectedNode.getCurrentTime();
- NameResolver resolver = connectedNode.getResolver().newChild("camera");
+ NameResolver resolver = connectedNode.getResolver().newChild("android_" + sID + "_camera");
imagePublisher =
connectedNode.newPublisher(resolver.resolve("image/compressed"), sensor_msgs.CompressedImage._TYPE);
cameraInfoPublisher =
diff --git a/android_core_components/src/main/java/org/ros/android/view/camera/RosCameraPreviewView.java b/android_core_components/src/main/java/org/ros/android/view/camera/RosCameraPreviewView.java
index b6c779b..2ced275 100644
--- a/android_core_components/src/main/java/org/ros/android/view/camera/RosCameraPreviewView.java
+++ b/android_core_components/src/main/java/org/ros/android/view/camera/RosCameraPreviewView.java
@@ -30,26 +30,20 @@ import org.ros.node.NodeMain;
*/
public class RosCameraPreviewView extends CameraPreviewView implements NodeMain {
- public RosCameraPreviewView(Context context) {
- super(context);
- }
+ private static String sID;
- public RosCameraPreviewView(Context context, AttributeSet attrs) {
- super(context, attrs);
- }
-
- public RosCameraPreviewView(Context context, AttributeSet attrs, int defStyle) {
- super(context, attrs, defStyle);
+ public RosCameraPreviewView(String nodeID){
+ sID = nodeID;
}
@Override
public GraphName getDefaultNodeName() {
- return GraphName.of("ros_camera_preview_view");
+ return GraphName.of("android_"+sID+"_camera");
}
@Override
public void onStart(ConnectedNode connectedNode) {
- setRawImageListener(new CompressedImagePublisher(connectedNode));
+ setRawImageListener(new CompressedImagePublisher(connectedNode, sID));
}
@Override
diff --git a/android_tutorial_camera_imu/res/values/strings.xml b/android_tutorial_camera_imu/res/values/strings.xml
index f930021..d9e4392 100644
--- a/android_tutorial_camera_imu/res/values/strings.xml
+++ b/android_tutorial_camera_imu/res/values/strings.xml
@@ -1,3 +1,4 @@
CameraImu
+ sID
diff --git a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/ImuPublisher.java b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/ImuPublisher.java
index 02efab7..d6bf62d 100644
--- a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/ImuPublisher.java
+++ b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/ImuPublisher.java
@@ -54,6 +54,7 @@ import org.ros.node.topic.Publisher;
* @author axelfurlan@gmail.com (Axel Furlan)
*/
public class ImuPublisher implements NodeMain {
+ private static String sID;
private ImuThread imuThread;
private SensorListener sensorListener;
private SensorManager sensorManager;
@@ -160,7 +161,7 @@ public class ImuPublisher implements NodeMain {
//long time_delta_millis = System.currentTimeMillis() - SystemClock.uptimeMillis();
//this.imu.getHeader().setStamp(Time.fromMillis(time_delta_millis + event.timestamp/1000000));
this.imu.getHeader().setStamp(connectedNode.getCurrentTime());
- this.imu.getHeader().setFrameId("/imu");// TODO Make parameter
+ this.imu.getHeader().setFrameId("/android_" + sID + "imu");// TODO Make parameter
publisher.publish(this.imu);
@@ -176,12 +177,13 @@ public class ImuPublisher implements NodeMain {
}
- public ImuPublisher(SensorManager manager) {
+ public ImuPublisher(SensorManager manager, String nodeID) {
this.sensorManager = manager;
+ sID = nodeID;
}
public GraphName getDefaultNodeName() {
- return GraphName.of("android_sensors_driver/imuPublisher");
+ return GraphName.of("android_" + sID + "/imuPublisher");
}
public void onError(Node node, Throwable throwable) {
@@ -190,7 +192,7 @@ public class ImuPublisher implements NodeMain {
public void onStart(ConnectedNode node) {
try {
this.connectedNode = node;
- this.publisher = node.newPublisher("android/imu", "sensor_msgs/Imu");
+ this.publisher = node.newPublisher("android_" + sID + "/imu", "sensor_msgs/Imu");
// Determine if we have the various needed sensors
boolean hasAccel = false;
boolean hasGyro = false;
diff --git a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/MainActivity.java b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/MainActivity.java
index 695360c..9038f89 100644
--- a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/MainActivity.java
+++ b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/MainActivity.java
@@ -17,6 +17,7 @@ package org.ros.android.android_tutorial_camera_imu;
import android.Manifest;
import android.annotation.TargetApi;
+import android.app.Activity;
import android.content.Context;
import android.content.pm.PackageManager;
import android.hardware.Camera;
@@ -29,11 +30,16 @@ import android.view.MotionEvent;
import android.view.Window;
import android.view.WindowManager;
import android.widget.Toast;
+
+import android.util.Log;
import org.ros.address.InetAddressFactory;
+import org.ros.android.MasterChooser;
import org.ros.android.RosActivity;
import org.ros.android.view.camera.RosCameraPreviewView;
import org.ros.node.NodeConfiguration;
import org.ros.node.NodeMainExecutor;
+import android.content.SharedPreferences;
+import java.util.Random;
/**
* @author ethan.rublee@gmail.com (Ethan Rublee)
@@ -52,6 +58,24 @@ public class MainActivity extends RosActivity {
private LocationManager mLocationManager;
private SensorManager mSensorManager;
+ private static String sID = "1234";
+
+ private void id(Activity act) {
+
+ SharedPreferences sharedPref = act.getPreferences(Context.MODE_PRIVATE);
+
+ sID = sharedPref.getString(getString(R.string.sID_key), "1234");
+ Log.e("E", MasterChooser.getResetNodePrefixButtonClicked()+ "");
+ if (sID.equals("1234") || MasterChooser.getResetNodePrefixButtonClicked()) {
+
+ sID = Integer.toString(new Random().nextInt(Integer.MAX_VALUE/2) + Integer.MAX_VALUE / 2);
+ sID = sID.replace("-","");
+ SharedPreferences.Editor editor = sharedPref.edit();
+ editor.putString(getString(R.string.sID_key), sID);
+ editor.commit();
+ }
+ }
+
public MainActivity() {
super("ROS", "Camera & Imu");
}
@@ -62,11 +86,7 @@ public class MainActivity extends RosActivity {
requestWindowFeature(Window.FEATURE_NO_TITLE);
getWindow().addFlags(WindowManager.LayoutParams.FLAG_FULLSCREEN);
- setContentView(R.layout.activity_main);
-
- rosCameraPreviewView = findViewById(R.id.ros_camera_preview_view);
- mLocationManager = (LocationManager) this.getSystemService(Context.LOCATION_SERVICE);
- mSensorManager = (SensorManager) this.getSystemService(SENSOR_SERVICE);
+ //setContentView(R.layout.activity_main);
}
@Override
@@ -96,6 +116,11 @@ public class MainActivity extends RosActivity {
@Override @TargetApi(Build.VERSION_CODES.ICE_CREAM_SANDWICH_MR1) //API = 15
protected void init(NodeMainExecutor nodeMainExecutor) {
+ id(this);
+ rosCameraPreviewView = new RosCameraPreviewView(sID);
+ mLocationManager = (LocationManager) this.getSystemService(Context.LOCATION_SERVICE);
+ mSensorManager = (SensorManager) this.getSystemService(SENSOR_SERVICE);
+
this.nodeMainExecutor = nodeMainExecutor;
if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.M) {
@@ -108,29 +133,29 @@ public class MainActivity extends RosActivity {
}else {
NodeConfiguration nodeConfiguration1 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration1.setMasterUri(getMasterUri());
- nodeConfiguration1.setNodeName("android_sensors_driver_nav_sat_fix");
- this.fix_pub = new NavSatFixPublisher(mLocationManager);
+ nodeConfiguration1.setNodeName("android_" + sID + "_nav_sat_fix");
+ this.fix_pub = new NavSatFixPublisher(mLocationManager, sID);
nodeMainExecutor.execute(this.fix_pub, nodeConfiguration1);
rosCameraPreviewView.setCamera(getCamera());
NodeConfiguration nodeConfiguration2 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration2.setMasterUri(getMasterUri());
- nodeConfiguration2.setNodeName("android_sensors_driver_camera");
+ nodeConfiguration2.setNodeName("android_" + sID + "_camera");
nodeMainExecutor.execute(this.rosCameraPreviewView, nodeConfiguration2);
}
NodeConfiguration nodeConfiguration3 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration3.setMasterUri(getMasterUri());
- nodeConfiguration3.setNodeName("android_sensors_driver_imu");
- this.imu_pub = new ImuPublisher(mSensorManager);
+ nodeConfiguration3.setNodeName("android_" + sID + "_imu");
+ this.imu_pub = new ImuPublisher(mSensorManager, sID);
nodeMainExecutor.execute(this.imu_pub, nodeConfiguration3);
}
private void executeGPS() {
NodeConfiguration nodeConfiguration1 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration1.setMasterUri(getMasterUri());
- nodeConfiguration1.setNodeName("android_sensors_driver_nav_sat_fix");
- this.fix_pub = new NavSatFixPublisher(mLocationManager);
+ nodeConfiguration1.setNodeName("android_" + sID + "_nav_sat_fix");
+ this.fix_pub = new NavSatFixPublisher(mLocationManager, sID);
nodeMainExecutor.execute(this.fix_pub, nodeConfiguration1);
}
@@ -138,7 +163,7 @@ public class MainActivity extends RosActivity {
rosCameraPreviewView.setCamera(getCamera());
NodeConfiguration nodeConfiguration2 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration2.setMasterUri(getMasterUri());
- nodeConfiguration2.setNodeName("android_sensors_driver_camera");
+ nodeConfiguration2.setNodeName("android_" + sID + "_camera");
nodeMainExecutor.execute(this.rosCameraPreviewView, nodeConfiguration2);
}
diff --git a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/NavSatFixPublisher.java b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/NavSatFixPublisher.java
index 30dd52e..d74f257 100644
--- a/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/NavSatFixPublisher.java
+++ b/android_tutorial_camera_imu/src/main/java/org/ros/android/android_tutorial_camera_imu/NavSatFixPublisher.java
@@ -55,6 +55,7 @@ import org.ros.node.topic.Publisher;
public class NavSatFixPublisher implements NodeMain {
private NavSatThread navSatThread;
+ private static String sID;
private LocationManager locationManager;
private NavSatListener navSatFixListener;
private Publisher publisher;
@@ -102,7 +103,7 @@ public class NavSatFixPublisher implements NodeMain {
NavSatFix fix = this.publisher.newMessage();
//fix.getHeader().setStamp(Time.fromMillis(System.currentTimeMillis()));
fix.getHeader().setStamp(connectedNode.getCurrentTime());
- fix.getHeader().setFrameId("/gps");
+ fix.getHeader().setFrameId("/android_"+sID+"_gps");
fix.getStatus().setStatus(currentStatus);
fix.getStatus().setService(NavSatStatus.SERVICE_GPS);
@@ -142,15 +143,16 @@ public class NavSatFixPublisher implements NodeMain {
}
}
- public NavSatFixPublisher(LocationManager manager) {
+ public NavSatFixPublisher(LocationManager manager, String nodeID) {
this.locationManager = manager;
+ sID = nodeID;
}
//@Override
public void onStart(ConnectedNode node) {
try {
this.connectedNode = node;
- this.publisher = node.newPublisher("android/fix", "sensor_msgs/NavSatFix");
+ this.publisher = node.newPublisher("android_" + sID + "/fix", "sensor_msgs/NavSatFix");
this.navSatFixListener = new NavSatListener(publisher);
this.navSatThread = new NavSatThread(this.locationManager, this.navSatFixListener);
this.navSatThread.start();
@@ -178,7 +180,7 @@ public class NavSatFixPublisher implements NodeMain {
}
public GraphName getDefaultNodeName() {
- return GraphName.of("android_sensors_driver/imuPublisher");
+ return GraphName.of("android_" + sID + "/imuPublisher");
}
public void onError(Node node, Throwable throwable) {