Updated Android application, modified Arduino Sketch to stop in case of

loss of signal.
This commit is contained in:
Daniele Verducci 2014-03-09 16:55:30 +01:00
parent 69e2a58c67
commit 8e3a1dbacf
23 changed files with 77 additions and 4 deletions

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 378 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 291 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 453 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 614 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 8.5 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 324 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 237 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 437 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 655 B

View File

@ -22,4 +22,31 @@
android:text="@string/srv" android:text="@string/srv"
android:textAppearance="?android:attr/textAppearanceLarge" /> android:textAppearance="?android:attr/textAppearanceLarge" />
<TextView
android:id="@+id/textView1"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_below="@+id/text"
android:layout_centerHorizontal="true"
android:layout_margin="10dp"
android:gravity="center_horizontal"
android:text="@string/explain" />
<Button
android:id="@+id/killserverbutton"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_below="@+id/textView1"
android:layout_centerHorizontal="true"
android:text="@string/killserver" />
<ImageButton
android:id="@+id/startvideo"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignParentRight="true"
android:layout_alignParentTop="true"
android:layout_margin="10dp"
android:src="@drawable/ic_device_access_video" />
</RelativeLayout> </RelativeLayout>

View File

@ -3,5 +3,7 @@
<string name="app_name">AndroidExplorerbotServer</string> <string name="app_name">AndroidExplorerbotServer</string>
<string name="srv">Server started</string> <string name="srv">Server started</string>
<string name="explain">Exiting with HOME key will keep the server running. To exit completly press BACK or use the button below.</string>
<string name="killserver">Kill server</string>
</resources> </resources>

View File

@ -21,4 +21,5 @@ package it.danieleverducci.explorerbotserver;
public class AppConfiguration { public class AppConfiguration {
public static final int PORT=6787; //The default server port public static final int PORT=6787; //The default server port
public static final boolean LOG_ENABLED=false; public static final boolean LOG_ENABLED=false;
public static final String DEFAULT_IPCAMERA_APP_PACKAGENAME="com.pas.webcam";
} }

View File

@ -23,10 +23,15 @@ import it.danieleverducci.explorerbot.objects.GamepadPosition;
import java.io.IOException; import java.io.IOException;
import android.app.Activity; import android.app.Activity;
import android.content.Intent;
import android.net.Uri;
import android.os.Bundle; import android.os.Bundle;
import android.view.View;
import android.view.View.OnClickListener;
public class MainActivity extends Activity implements OnControllerPolledListener { public class MainActivity extends Activity implements OnControllerPolledListener, OnClickListener {
private SerialCommunication serial; private SerialCommunication serial;
private ServerNetworkCommunicationThread sct;
@Override @Override
protected void onCreate(Bundle savedInstanceState) { protected void onCreate(Bundle savedInstanceState) {
@ -37,10 +42,13 @@ public class MainActivity extends Activity implements OnControllerPolledListener
serial = new SerialCommunication(this); serial = new SerialCommunication(this);
//Start network communication server //Start network communication server
ServerNetworkCommunicationThread sct = new ServerNetworkCommunicationThread(); sct = new ServerNetworkCommunicationThread();
sct.setOnControllerPolledListener(this); sct.setOnControllerPolledListener(this);
sct.start(); sct.start();
//Register interface buttons listener
findViewById(R.id.killserverbutton).setOnClickListener(this);
findViewById(R.id.startvideo).setOnClickListener(this);
} }
@Override @Override
@ -56,6 +64,11 @@ public class MainActivity extends Activity implements OnControllerPolledListener
@Override @Override
protected void onDestroy() { protected void onDestroy() {
//Terminate network thread
if(sct!=null && sct.isAlive()){
sct.setMustExit(true);
}
//Terminate serial connection to Arduino
if(serial!=null){ if(serial!=null){
try { try {
serial.closeConnection(); serial.closeConnection();
@ -66,4 +79,25 @@ public class MainActivity extends Activity implements OnControllerPolledListener
super.onDestroy(); super.onDestroy();
} }
@Override
public void onClick(View v) {
switch(v.getId()){
case R.id.killserverbutton:
finish(); //Finishing the activity, onDestroy will be called
break;
case R.id.startvideo:
launchStreamingApp();
break;
}
}
/**
* If the app is installed, start it. Otherwise, open the Android Market for download
*/
private void launchStreamingApp() {
Intent launchIntent = getPackageManager().getLaunchIntentForPackage(AppConfiguration.DEFAULT_IPCAMERA_APP_PACKAGENAME);
if(launchIntent==null) launchIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("market://details?id=" + AppConfiguration.DEFAULT_IPCAMERA_APP_PACKAGENAME));
startActivity( launchIntent );
}
} }

View File

@ -37,6 +37,7 @@ const int hBridge2pin = 10;
#include <Servo.h> #include <Servo.h>
Servo steeringServo; Servo steeringServo;
byte gamepadPosition[2]; byte gamepadPosition[2];
byte missedUpdates=0;
void setup(){ void setup(){
steeringServo.attach(servoPin); //steering servo to pin 7 steeringServo.attach(servoPin); //steering servo to pin 7
@ -48,8 +49,16 @@ void setup(){
void loop(){ void loop(){
if(readGamepadPositionFromSerial()){ if(readGamepadPositionFromSerial()){
missedUpdates=0;
//If data ready, drive motors
steerTo(gamepadPosition[0]); steerTo(gamepadPosition[0]);
accelerateTo(gamepadPosition[1]); accelerateTo(gamepadPosition[1]);
} else {
//If data not ready for 5 times (500ms), stop the robot (for security reasons, e.g. the connection may be dropped)
missedUpdates++;
if(missedUpdates>5){
accelerateTo(63);
}
} }
delay(100); delay(100);
} }
@ -80,6 +89,6 @@ void accelerateTo(byte speedByte){
//speedByte = speedByte-64; //speedByte = speedByte-64;
} }
//analogWrite(hBridgeEnable, speedByte*2); //analogWrite(hBridgeEnable, speedByte*2);
if(speedByte<32 || speedByte>96) digitalWrite(hBridgeEnable, HIGH); if(speedByte<47 || speedByte>79) digitalWrite(hBridgeEnable, HIGH);
else digitalWrite(hBridgeEnable, LOW); else digitalWrite(hBridgeEnable, LOW);
} }