Compare commits

...

3 Commits

Author SHA1 Message Date
yikestone
ad1e819595 Added UI for manually setting Node prefix.
Added on demand Node start and shutdown switch.
Added radio buttons for changing camera resolution.
2020-08-10 07:33:30 +05:30
yikestone
50a3edbfa6 Changed default resolution to 640x480 2020-08-08 21:41:07 +05:30
yikestone
48600d7496 Added Reset Node Prefix, so that multiple Android phones can connect to same ROS MASTER.
Camera node now runs in background even when screen is off.
2020-08-07 10:32:16 +05:30
11 changed files with 199 additions and 162 deletions

View File

@ -62,6 +62,7 @@
android:onClick="advancedCheckboxClicked"
android:text="@string/show_advanced"/>
<LinearLayout
android:orientation="vertical"
android:layout_width="fill_parent"
@ -119,7 +120,14 @@
android:layout_gravity="bottom"
android:onClick="cancelButtonClicked"
android:text="@string/cancel"/>
<Button
android:id="@+id/reset_node_prefix"
style="@style/padded"
android:layout_width="fill_parent"
android:layout_height="wrap_content"
android:layout_gravity="bottom"
android:onClick="resetNodePrefixButtonClicked"
android:text="@string/reset_node_prefix"/>
<LinearLayout
android:id="@+id/connection_layout"
android:layout_width="match_parent"

View File

@ -4,6 +4,7 @@
<string name="app_name">ROS for Android</string>
<string name="use_master">Connect</string>
<string name="cancel">Cancel</string>
<string name="reset_node_prefix">Reset Prefix</string>
<string name="qr_code">Read QRCode</string>
<string name="master_uri_hint">http://localhost:11311/</string>
<string name="new_master">New Public Master</string>

View File

@ -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);

View File

@ -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<Size> supportedPreviewSizes = parameters.getSupportedPreviewSizes();
previewSize = getOptimalPreviewSize(supportedPreviewSizes, getWidth(), getHeight());
previewSize = getOptimalPreviewSize(supportedPreviewSizes, 640, 480);
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);
}
}
}
}

View File

@ -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 =

View File

@ -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

View File

@ -50,7 +50,7 @@ public class MainActivity extends RosActivity {
requestWindowFeature(Window.FEATURE_NO_TITLE);
getWindow().addFlags(WindowManager.LayoutParams.FLAG_FULLSCREEN);
setContentView(R.layout.main);
rosCameraPreviewView = (RosCameraPreviewView) findViewById(R.id.ros_camera_preview_view);
//rosCameraPreviewView = (RosCameraPreviewView) findViewById(R.id.ros_camera_preview_view);
}
@Override

View File

@ -1,3 +1,4 @@
<resources>
<string name="app_name">CameraImu</string>
<string name="sID_key">sID</string>
</resources>

View File

@ -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;

View File

@ -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;
@ -26,14 +27,23 @@ import android.os.Build;
import android.os.Bundle;
import android.support.v4.app.ActivityCompat;
import android.view.MotionEvent;
import android.view.View;
import android.view.Window;
import android.view.WindowManager;
import android.widget.CompoundButton;
import android.widget.RadioButton;
import android.widget.Switch;
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)
@ -48,9 +58,18 @@ public class MainActivity extends RosActivity {
private NavSatFixPublisher fix_pub;
private ImuPublisher imu_pub;
private Switch cameraSwitch;
private Switch imuSwitch;
private Switch gpsSwitch;
private boolean cameraRunning;
private NodeMainExecutor nodeMainExecutor;
private LocationManager mLocationManager;
private SensorManager mSensorManager;
private static String sID = "";
private NodeConfiguration nodeConfigurationGPS, nodeConfigurationCamera, nodeConfigurationImu;
public MainActivity() {
super("ROS", "Camera & Imu");
@ -60,28 +79,76 @@ public class MainActivity extends RosActivity {
protected void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
requestWindowFeature(Window.FEATURE_NO_TITLE);
getWindow().addFlags(WindowManager.LayoutParams.FLAG_FULLSCREEN);
setContentView(R.layout.activity_main);
cameraRunning = false;
cameraSwitch = (Switch) findViewById(R.id.camera_switch);
imuSwitch = (Switch) findViewById(R.id.imu_switch);
gpsSwitch = (Switch) findViewById(R.id.gps_switch);
rosCameraPreviewView = findViewById(R.id.ros_camera_preview_view);
mLocationManager = (LocationManager) this.getSystemService(Context.LOCATION_SERVICE);
mSensorManager = (SensorManager) this.getSystemService(SENSOR_SERVICE);
imuSwitch.setOnCheckedChangeListener(new CompoundButton.OnCheckedChangeListener() {
@Override
public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) {
if(isChecked)
nodeMainExecutor.execute(imu_pub, nodeConfigurationImu);
else
nodeMainExecutor.shutdownNodeMain(imu_pub);
Log.v("IMU publisher", ""+isChecked);
}
});
gpsSwitch.setOnCheckedChangeListener(new CompoundButton.OnCheckedChangeListener() {
@Override
public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) {
if(isChecked)
nodeMainExecutor.execute(fix_pub, nodeConfigurationGPS);
else
nodeMainExecutor.shutdownNodeMain(fix_pub);
Log.v("IMU publisher", ""+isChecked);
}
});
cameraSwitch.setOnCheckedChangeListener(new CompoundButton.OnCheckedChangeListener() {
@Override
public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) {
if(isChecked) {
rosCameraPreviewView.setCamera(getCamera());
nodeMainExecutor.execute(rosCameraPreviewView, nodeConfigurationCamera);
cameraRunning = true;
}
else {
nodeMainExecutor.shutdownNodeMain(rosCameraPreviewView);
cameraRunning = false;
}
Log.v("IMU publisher", ""+isChecked);
}
});
}
@Override
public boolean onTouchEvent(MotionEvent event) {
//if (Build.VERSION.SDK_INT < Build.VERSION_CODES.P) {
if (event.getAction() == MotionEvent.ACTION_UP) {
int numberOfCameras = Camera.getNumberOfCameras();
final Toast toast;
if (numberOfCameras > 1) {
cameraId = (cameraId + 1) % numberOfCameras;
rosCameraPreviewView.releaseCamera();
rosCameraPreviewView.setCamera(getCamera());
toast = Toast.makeText(this, "Switching cameras.", Toast.LENGTH_SHORT);
} else {
toast = Toast.makeText(this, "No alternative cameras to switch to.", Toast.LENGTH_SHORT);
public void onSwitchCameraButtonClicked(View view) {
final Toast toast;
if(!cameraRunning)
{
toast = Toast.makeText(this, "Camera Publisher not running", Toast.LENGTH_SHORT);
}
else {
int numberOfCameras = Camera.getNumberOfCameras();
if (numberOfCameras > 1) {
cameraId = (cameraId + 1) % numberOfCameras;
rosCameraPreviewView.releaseCamera();
rosCameraPreviewView.setCamera(getCamera());
toast = Toast.makeText(this, "Switching cameras.", Toast.LENGTH_SHORT);
} else {
toast = Toast.makeText(this, "No alternative cameras to switch to.", Toast.LENGTH_SHORT);
}
}
runOnUiThread(new Runnable() {
@Override
@ -89,13 +156,15 @@ public class MainActivity extends RosActivity {
toast.show();
}
});
}
//}
return true;
}
@Override @TargetApi(Build.VERSION_CODES.ICE_CREAM_SANDWICH_MR1) //API = 15
protected void init(NodeMainExecutor nodeMainExecutor) {
sID = MasterChooser.sID;
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) {
@ -106,40 +175,32 @@ public class MainActivity extends RosActivity {
PERMISSIONS[3] = Manifest.permission.WRITE_EXTERNAL_STORAGE;
ActivityCompat.requestPermissions(this, PERMISSIONS, 0);
}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);
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");
nodeMainExecutor.execute(this.rosCameraPreviewView, nodeConfiguration2);
initGPS();
initCamera();
}
initImu();
NodeConfiguration nodeConfiguration3 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration3.setMasterUri(getMasterUri());
nodeConfiguration3.setNodeName("android_sensors_driver_imu");
this.imu_pub = new ImuPublisher(mSensorManager);
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);
nodeMainExecutor.execute(this.fix_pub, nodeConfiguration1);
private void initGPS() {
this.fix_pub = new NavSatFixPublisher(mLocationManager, sID);
nodeConfigurationGPS = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfigurationGPS.setMasterUri(getMasterUri());
nodeConfigurationGPS.setNodeName(fix_pub.getDefaultNodeName());
}
private void executeCamera() {
private void initCamera() {
rosCameraPreviewView.setCamera(getCamera());
NodeConfiguration nodeConfiguration2 = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfiguration2.setMasterUri(getMasterUri());
nodeConfiguration2.setNodeName("android_sensors_driver_camera");
nodeMainExecutor.execute(this.rosCameraPreviewView, nodeConfiguration2);
nodeConfigurationCamera = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfigurationCamera.setMasterUri(getMasterUri());
nodeConfigurationCamera.setNodeName(rosCameraPreviewView.getDefaultNodeName());
}
private void initImu() {
nodeConfigurationImu = NodeConfiguration.newPublic(InetAddressFactory.newNonLoopback().getHostAddress());
nodeConfigurationImu.setMasterUri(getMasterUri());
this.imu_pub = new ImuPublisher(mSensorManager, sID);
nodeConfigurationImu.setNodeName(imu_pub.getDefaultNodeName());
}
private Camera getCamera() {
@ -147,10 +208,10 @@ public class MainActivity extends RosActivity {
Camera.Parameters camParams = cam.getParameters();
if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.ICE_CREAM_SANDWICH) {
if (camParams.getSupportedFocusModes().contains(
Camera.Parameters.FOCUS_MODE_CONTINUOUS_VIDEO)) {
camParams.setFocusMode(Camera.Parameters.FOCUS_MODE_CONTINUOUS_VIDEO);
Camera.Parameters.FOCUS_MODE_INFINITY)) {
camParams.setFocusMode(Camera.Parameters.FOCUS_MODE_INFINITY);
} else {
camParams.setFocusMode(Camera.Parameters.FOCUS_MODE_CONTINUOUS_PICTURE);
camParams.setFocusMode(Camera.Parameters.FOCUS_MODE_INFINITY);
}
}
//cam.setParameters(camParams);
@ -163,17 +224,41 @@ public class MainActivity extends RosActivity {
if (requestCode == 0) {
if (grantResults.length > 0 && grantResults[0] == PackageManager.PERMISSION_GRANTED) {
// permission was granted, yay! Do the
executeGPS();
initGPS();
}
if (grantResults.length > 1 && grantResults[1] == PackageManager.PERMISSION_GRANTED) {
// permission was granted, yay! Do the
executeCamera();
}
if (grantResults.length > 2 && grantResults[2] == PackageManager.PERMISSION_GRANTED &&
grantResults[3] == PackageManager.PERMISSION_GRANTED) {
// permission was granted, yay! Do the
initCamera();
}
}
}
public void onRadioButtonClicked(View view) {
boolean checked = ((RadioButton) view).isChecked();
switch(view.getId()) {
case R.id.res480:
if (checked)
rosCameraPreviewView.setPreviewSize(640, 480);
break;
case R.id.res720:
if (checked)
rosCameraPreviewView.setPreviewSize(1280, 720);
break;
case R.id.res1080:
if (checked)
rosCameraPreviewView.setPreviewSize(1920, 1080);
break;
}
if(cameraRunning){
rosCameraPreviewView.releaseCamera();
rosCameraPreviewView.setCamera(getCamera());
}
}
}

View File

@ -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<NavSatFix> 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) {