Skip to content

Commit 7828d74

Browse files
Merge pull request #997 from TShapinsky/voice_settings
Periodic Speech Output Settings and Functionality
2 parents 85f2e07 + f8d3dd9 commit 7828d74

File tree

9 files changed

+195
-11
lines changed

9 files changed

+195
-11
lines changed

Android/res/values/arrays.xml

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,20 @@
202202
<item>20;ElevatorWithInput</item>
203203
<item>21;Rudder</item>
204204
</string-array>
205-
205+
<string-array name="tts_periodic_period">
206+
<item>off</item>
207+
<item>15 sec.</item>
208+
<item>30 sec.</item>
209+
<item>45 sec.</item>
210+
<item>60 sec.</item>
211+
</string-array>
212+
<string-array name="tts_periodic_period_values">
213+
<item>0</item>
214+
<item>15</item>
215+
<item>30</item>
216+
<item>45</item>
217+
<item>60</item>
218+
</string-array>
206219
<!-- This string is just used to help in the layout editor -->
207220
<string-array name="ExampleCameraArray">
208221
<item>No cameras Available</item>

Android/res/values/preferences_keys.xml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,4 +39,11 @@ This file is used to store the preferences keys so that it's accessible and modi
3939
<string name="pref_dshare_password_key">dshare_password</string>
4040
<string name="pref_dshare_enabled_key">dshare_enabled</string>
4141
<string name="pref_live_upload_enabled_key">pref_live_upload_enabled</string>
42+
43+
<string name="pref_tts_periodic_key">tts_periodic</string>
44+
<string name="pref_tts_periodic_period_key">tts_periodic_period</string>
45+
<string name="pref_tts_periodic_bat_volt_key">tts_periodic_bat_volt</string>
46+
<string name="pref_tts_periodic_alt_key">tts_periodic_alt</string>
47+
<string name="pref_tts_periodic_rssi_key">tts_periodic_rssi</string>
48+
<string name="pref_tts_periodic_airspeed_key">tts_periodic_airspeed</string>
4249
</resources>

Android/res/values/strings.xml

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -361,6 +361,21 @@
361361
<string name="ga_mode_details_open_panel">Panel Open Time</string>
362362
<string name="ga_mode_details_close_panel">Panel Close Time</string>
363363

364+
<!-- Text To Speach -->
365+
<string name="pref_title_tts">Speech Output</string>
366+
<string name="pref_title_tts_periodic">Periodic</string>
367+
<string name="pref_tts_periodic_summary">What is included in the periodic status.</string>
368+
<string name="pref_tts_periodic_period">Period</string>
369+
<string name="pref_tts_periodic_period_summary">How often periodic status is read.</string>
370+
<string name="pref_tts_periodic_bat_volt">Battery Voltage</string>
371+
<string name="pref_tts_periodic_bat_volt_summary">Read battery voltage.</string>
372+
<string name="pref_tts_periodic_alt">Altitude</string>
373+
<string name="pref_tts_periodic_alt_summary">Read altitude.</string>
374+
<string name="pref_tts_periodic_rssi">Signal Strength (RSSI)</string>
375+
<string name="pref_tts_periodic_rssi_summary">Read recieved signal strength indication.</string>
376+
<string name="pref_tts_periodic_airspeed">Airspeed</string>
377+
<string name="pref_tts_periodic_airspeed_summary">Read airspeed.</string>
378+
364379
<!-- Others (when possible move to a grouping above) -->
365380
<string name="tune_roll">Manual adjustment of roll and pitch tuning. Rate_P is the primary value to adjust.</string>
366381
<string name="dialog_box_title_altitude">Altitude</string>

Android/res/xml/preferences.xml

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,40 @@
7171
android:title="@string/pref_request_max_volume" />
7272
</PreferenceCategory>
7373
</PreferenceScreen>
74+
<PreferenceScreen android:title="@string/pref_title_tts">
75+
<PreferenceCategory android:title="@string/pref_title_tts_periodic"
76+
android:summary="@string/pref_tts_periodic_summary"
77+
android:key="@string/pref_tts_periodic_key">
78+
<ListPreference
79+
android:title="@string/pref_tts_periodic_period"
80+
android:entries="@array/tts_periodic_period"
81+
android:entryValues="@array/tts_periodic_period_values"
82+
android:key="@string/pref_tts_periodic_period_key"
83+
android:summary="@string/pref_tts_periodic_period_summary"
84+
android:defaultValue="off"/>
85+
<CheckBoxPreference
86+
android:title="@string/pref_tts_periodic_bat_volt"
87+
android:key="@string/pref_tts_periodic_bat_volt_key"
88+
android:summary="@string/pref_tts_periodic_bat_volt_summary"
89+
android:defaultValue="true"/>
90+
<CheckBoxPreference
91+
android:title="@string/pref_tts_periodic_alt"
92+
android:key="@string/pref_tts_periodic_alt_key"
93+
android:summary="@string/pref_tts_periodic_alt_summary"
94+
android:defaultValue="true"/>
95+
<CheckBoxPreference
96+
android:title="@string/pref_tts_periodic_airspeed"
97+
android:key="@string/pref_tts_periodic_airspeed_key"
98+
android:summary="@string/pref_tts_periodic_airspeed_summary"
99+
android:defaultValue="true"/>
100+
<CheckBoxPreference
101+
android:title="@string/pref_tts_periodic_rssi"
102+
android:key="@string/pref_tts_periodic_rssi_key"
103+
android:summary="@string/pref_tts_periodic_rssi_summary"
104+
android:defaultValue="true"/>
105+
106+
</PreferenceCategory>
107+
</PreferenceScreen>
74108

75109
<!-- Droneshare preferences section -->
76110
<PreferenceScreen

Android/src/org/droidplanner/android/DroidPlannerApp.java

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
import android.content.Context;
2121
import android.os.SystemClock;
22+
import android.widget.Toast;
2223

2324
import com.MAVLink.Messages.MAVLinkMessage;
2425

@@ -29,7 +30,7 @@ public class DroidPlannerApp extends ErrorReportApp implements MAVLinkStreams.Ma
2930
public Follow followMe;
3031
public MissionProxy missionProxy;
3132
private MavLinkMsgHandler mavLinkMsgHandler;
32-
33+
private DroidPlannerPrefs prefs;
3334
/**
3435
* Handles dispatching of status bar, and audible notification.
3536
*/
@@ -40,7 +41,6 @@ public void onCreate() {
4041
super.onCreate();
4142

4243
final Context context = getApplicationContext();
43-
mNotificationHandler = new NotificationHandler(context);
4444

4545
MAVLinkClient MAVClient = new MAVLinkClient(this, this);
4646
Clock clock = new Clock() {
@@ -62,9 +62,10 @@ public void postDelayed(Runnable thread, long timeout) {
6262
handler.postDelayed(thread, timeout);
6363
}
6464
};
65+
mNotificationHandler = new NotificationHandler(context, handler);
6566

66-
DroidPlannerPrefs pref = new DroidPlannerPrefs(context);
67-
drone = new DroneImpl(MAVClient, clock, handler, pref);
67+
prefs = new DroidPlannerPrefs(context);
68+
drone = new DroneImpl(MAVClient, clock, handler, prefs);
6869
getDrone().addDroneListener(this);
6970

7071
missionProxy = new MissionProxy(getDrone().getMission());
@@ -109,6 +110,10 @@ public void onDroneEvent(DroneEventsType event, Drone drone) {
109110
}
110111
}
111112

113+
public DroidPlannerPrefs getPreferences(){
114+
return prefs;
115+
}
116+
112117
public Drone getDrone() {
113118
return drone;
114119
}

Android/src/org/droidplanner/android/fragments/SettingsFragment.java

Lines changed: 28 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import org.droidplanner.android.activities.helpers.MapPreferencesActivity;
1515
import org.droidplanner.android.communication.service.UploaderService;
1616
import org.droidplanner.android.maps.providers.DPMapProvider;
17+
import org.droidplanner.android.notifications.TTSNotificationProvider;
1718
import org.droidplanner.android.utils.file.DirectoryPath;
1819
import org.droidplanner.core.model.Drone;
1920
import org.droidplanner.core.drone.DroneInterfaces;
@@ -35,6 +36,7 @@
3536
import android.preference.Preference.OnPreferenceClickListener;
3637
import android.preference.PreferenceCategory;
3738
import android.preference.PreferenceManager;
39+
import android.preference.PreferenceScreen;
3840
import android.util.Log;
3941
import android.widget.Toast;
4042

@@ -97,6 +99,8 @@ public boolean onPreferenceClick(Preference preference) {
9799
}
98100
}
99101

102+
setupPeriodicControls();
103+
100104
// Populate the map preference category
101105
final String mapsProvidersPrefKey = getString(R.string.pref_maps_providers_key);
102106
final ListPreference mapsProvidersPref = (ListPreference) findPreference(mapsProvidersPrefKey);
@@ -367,8 +371,9 @@ public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, Strin
367371
+ getString(R.string.set_to_zero_to_disable));
368372
}
369373

374+
DroidPlannerApp droidPlannerApp = (DroidPlannerApp) getActivity().getApplication();
370375
if (key.equals(getString(R.string.pref_vehicle_type_key))) {
371-
((DroidPlannerApp) getActivity().getApplication()).getDrone().notifyDroneEvent(DroneEventsType.TYPE);
376+
droidPlannerApp.getDrone().notifyDroneEvent(DroneEventsType.TYPE);
372377
}
373378

374379
if (key.equals(getString(R.string.pref_rc_mode_key))) {
@@ -378,6 +383,28 @@ public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, Strin
378383
preference.setSummary(R.string.mode2_throttle_on_left_stick);
379384
}
380385
}
386+
387+
if(key.equals(getString(R.string.pref_tts_periodic_period_key))){
388+
setupPeriodicControls();
389+
int val = Integer.parseInt(sharedPreferences.getString(getString(R.string.pref_tts_periodic_period_key), null));
390+
if(droidPlannerApp.getDrone().getMavClient().isConnected()) {
391+
droidPlannerApp.mNotificationHandler.getTtsNotification().setupPeriodicSpeechOutput(val, droidPlannerApp.getDrone());
392+
}
393+
}
394+
}
395+
396+
private void setupPeriodicControls(){
397+
final PreferenceCategory periodicSpeechPrefs = (PreferenceCategory) findPreference(getActivity().getApplicationContext().getString(R.string.pref_tts_periodic_key));
398+
ListPreference periodic = ((ListPreference) periodicSpeechPrefs.getPreference(0));
399+
int val = Integer.parseInt(periodic.getValue());
400+
if(val != 0) {
401+
periodic.setSummary("Status every " + val + " seconds");
402+
}else{
403+
periodic.setSummary("Status disabled");
404+
}
405+
for(int i = 1; i < periodicSpeechPrefs.getPreferenceCount(); i ++) {
406+
periodicSpeechPrefs.getPreference(i).setEnabled(val != 0);
407+
}
381408
}
382409

383410
@Override

Android/src/org/droidplanner/android/notifications/NotificationHandler.java

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
import org.droidplanner.core.model.Drone;
44
import org.droidplanner.core.drone.DroneInterfaces;
5-
5+
import org.droidplanner.core.drone.DroneInterfaces.Handler;
66
import android.content.Context;
77

88
/**
@@ -19,6 +19,7 @@ interface NotificationProvider extends DroneInterfaces.OnDroneListener {
1919
void quickNotify(String feedback);
2020
}
2121

22+
2223
/**
2324
* Handles Droidplanner's audible notifications.
2425
*/
@@ -34,8 +35,8 @@ interface NotificationProvider extends DroneInterfaces.OnDroneListener {
3435
*/
3536
private final PebbleNotificationProvider mPebbleNotification;
3637

37-
public NotificationHandler(Context context) {
38-
mTtsNotification = new TTSNotificationProvider(context);
38+
public NotificationHandler(Context context, Handler handler) {
39+
mTtsNotification = new TTSNotificationProvider(context, handler);
3940
mStatusBarNotification = new StatusBarNotificationProvider(context);
4041
mPebbleNotification = new PebbleNotificationProvider(context);
4142
}
@@ -50,12 +51,16 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, Drone drone) {
5051
/**
5152
* Sends a quick notification to the user. Uses toasts for written
5253
* notification, and speech if voice notification is enabled.
53-
*
54+
*
5455
* @param feedback
5556
* short message to show the user.
5657
*/
5758
public void quickNotify(String feedback) {
5859
mTtsNotification.quickNotify(feedback);
5960
mStatusBarNotification.quickNotify(feedback);
6061
}
62+
63+
public TTSNotificationProvider getTtsNotification() {
64+
return mTtsNotification;
65+
}
6166
}

Android/src/org/droidplanner/android/notifications/TTSNotificationProvider.java

Lines changed: 62 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,15 @@
11
package org.droidplanner.android.notifications;
22

33
import java.util.Locale;
4+
import java.util.Map;
45

56
import org.droidplanner.R;
7+
import org.droidplanner.android.DroidPlannerApp;
8+
import org.droidplanner.android.utils.prefs.DroidPlannerPrefs;
69
import org.droidplanner.core.model.Drone;
710
import org.droidplanner.core.drone.DroneInterfaces.DroneEventsType;
811
import org.droidplanner.core.drone.variables.Calibration;
12+
import org.droidplanner.core.drone.DroneInterfaces.Handler;
913

1014
import android.content.Context;
1115
import android.content.SharedPreferences;
@@ -33,11 +37,25 @@ public class TTSNotificationProvider implements OnInitListener,
3337
private int lastBatteryDischargeNotification;
3438

3539
private Context context;
40+
private Handler handler;
41+
private int statusInterval;
42+
private class Watchdog implements Runnable{
43+
private Drone drone;
44+
public void run() {
45+
speakPeriodic(drone);
46+
}
47+
48+
public void setDrone(Drone drone){
49+
this.drone = drone;
50+
}
51+
}
52+
public Watchdog watchdogCallback = new Watchdog();
3653

37-
TTSNotificationProvider(Context context) {
54+
TTSNotificationProvider(Context context, Handler handler) {
3855
this.context = context;
3956
tts = new TextToSpeech(context, this);
4057
this.prefs = PreferenceManager.getDefaultSharedPreferences(context);
58+
this.handler = handler;
4159
}
4260

4361
@Override
@@ -123,16 +141,24 @@ public void onDroneEvent(DroneEventsType event, Drone drone) {
123141
speak("Waypoints received");
124142
break;
125143
case HEARTBEAT_FIRST:
144+
statusInterval = new DroidPlannerPrefs(context).getSpokenStatusInterval();
145+
setupPeriodicSpeechOutput(statusInterval, drone);
126146
speak("Connected");
127147
break;
128148
case HEARTBEAT_TIMEOUT:
129149
if (!Calibration.isCalibrating()) {
130150
speak("Data link lost, check connection.");
151+
handler.removeCallbacks(watchdogCallback);
131152
}
132153
break;
133154
case HEARTBEAT_RESTORED:
155+
statusInterval = new DroidPlannerPrefs(context).getSpokenStatusInterval();
156+
setupPeriodicSpeechOutput(statusInterval, drone);
134157
speak("Data link restored");
135158
break;
159+
case DISCONNECTED:
160+
handler.removeCallbacks(watchdogCallback);
161+
break;
136162
case MISSION_WP_UPDATE:
137163
speak("Going for waypoint " + drone.getMissionStats().getCurrentWP());
138164
break;
@@ -209,6 +235,41 @@ private void speakGpsMode(int fix) {
209235
}
210236
}
211237

238+
private void speakPeriodic(Drone drone){
239+
DroidPlannerPrefs preferences = new DroidPlannerPrefs(context);
240+
Map<String,Boolean> speechPrefs = preferences.getPeriodicSpeechPrefs();
241+
StringBuilder message = new StringBuilder();
242+
if(speechPrefs.get("battery voltage")){
243+
message.append("battery " + drone.getBattery().getBattVolt() + " volts. ");
244+
}
245+
if(speechPrefs.get("altitude")){
246+
message.append("altitude, " + (int)(drone.getAltitude().getAltitude()*10.0)/10.0 + " meters. ");
247+
}
248+
if(speechPrefs.get("airspeed")){
249+
message.append("airspeed, " + (int)(drone.getSpeed().getAirSpeed().valueInMetersPerSecond()*10.0)/10.0 + " meters per second. ");
250+
}
251+
if(speechPrefs.get("rssi")){
252+
message.append("r s s i, " + drone.getRadio().getRssi() + " decibels");
253+
}
254+
speak(message.toString());
255+
if(preferences.getSpokenStatusInterval() != 0) {
256+
handler.postDelayed(watchdogCallback, statusInterval * 1000);
257+
}else{
258+
handler.removeCallbacks(watchdogCallback);
259+
}
260+
}
261+
262+
public void setupPeriodicSpeechOutput(int interval, Drone drone){
263+
watchdogCallback.setDrone(drone);
264+
if(interval == 0){
265+
handler.removeCallbacks(watchdogCallback);
266+
}else{
267+
statusInterval = interval;
268+
handler.removeCallbacks(watchdogCallback);
269+
handler.postDelayed(watchdogCallback,interval*1000);
270+
}
271+
}
272+
212273
@Override
213274
public void quickNotify(String feedback) {
214275
speak(feedback);

Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
package org.droidplanner.android.utils.prefs;
22

3+
import java.util.HashMap;
4+
import java.util.Map;
35
import java.util.UUID;
46

57
import org.droidplanner.R;
@@ -255,4 +257,19 @@ public boolean isEnglishDefaultLanguage() {
255257
public String getMapProviderName() {
256258
return prefs.getString(context.getString(R.string.pref_maps_providers_key), null);
257259
}
260+
261+
public Map<String,Boolean> getPeriodicSpeechPrefs(){
262+
Map<String,Boolean> speechPrefs = new HashMap<String, Boolean>();
263+
speechPrefs.put("battery voltage", prefs.getBoolean(context.getString(R.string.pref_tts_periodic_bat_volt_key),true));
264+
speechPrefs.put("altitude", prefs.getBoolean(context.getString(R.string.pref_tts_periodic_alt_key),true));
265+
speechPrefs.put("airspeed", prefs.getBoolean(context.getString(R.string.pref_tts_periodic_airspeed_key),true));
266+
speechPrefs.put("rssi", prefs.getBoolean(context.getString(R.string.pref_tts_periodic_rssi_key),true));
267+
return speechPrefs;
268+
}
269+
270+
public int getSpokenStatusInterval(){
271+
return Integer.parseInt(prefs.getString(context.getString(R.string.pref_tts_periodic_period_key), null));
272+
}
273+
274+
258275
}

0 commit comments

Comments
 (0)