@@ -78,6 +78,9 @@ int voltage_buffer_index1 = 0;
78
78
float voltage_buffer2[MOVING_AVERAGE_SAMPLES];
79
79
int voltage_buffer_index2 = 0 ;
80
80
81
+ String status_new = " Touch 2nd row for surprise" ;
82
+ String status_old = " " ;
83
+
81
84
// ===== Thruster/Devices Variables =====
82
85
uint16_t microseconds[] = {1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 , 1500 };
83
86
int Sthrusters[8 ];
@@ -112,11 +115,11 @@ Button buttons[] = {
112
115
{184 , 110 , 44 , 48 , LABEL_COLOR, " FC" },
113
116
{230 , 110 , 44 , 48 , LABEL_COLOR, " DC" },
114
117
{276 , 110 , 44 , 48 , LABEL_COLOR, " DVL" },
115
- {0 , 164 , 320 , 30 , MAIN_RECT_COLOR, " Touch 2nd row for surprise " },
118
+ {0 , 164 , 320 , 30 , MAIN_RECT_COLOR, status_new },
116
119
{0 , 200 , 78 , 35 , RED, " T" },
117
120
{80 , 200 , 78 , 35 , RED, " DB" },
118
121
{160 , 200 , 78 , 35 , RED, " Celine" },
119
- {240 , 200 , 78 , 35 , RED, " Celine " },
122
+ {240 , 200 , 78 , 35 , RED, " Mia " },
120
123
};
121
124
122
125
// Thruster buttons for main page
@@ -290,6 +293,28 @@ void thrusterStatus(int Sthrusters[]) {
290
293
Sthrusters[i] = 1 ;
291
294
}
292
295
}
296
+
297
+ }
298
+
299
+ // == Status Update Functions === //
300
+
301
+ void updateStatusDisplay (String newStatus) {
302
+ if (newStatus != status_old) {
303
+ tft.fillRoundRect (0 , 164 , 320 , 30 , 8 , MAIN_RECT_COLOR);
304
+
305
+ delay (2000 );
306
+
307
+ tft.setTextColor (BLACK);
308
+ tft.setTextSize (2 );
309
+
310
+ int16_t x, y;
311
+ uint16_t w, h;
312
+ tft.getTextBounds (newStatus, 0 ,0 , &x, &y, &w, &h);
313
+ tft.setCursor ((320 -w)/2 , 164 + (30 - h) / 2 );
314
+ tft.print (newStatus);
315
+
316
+ status_old = newStatus;
317
+ }
293
318
}
294
319
295
320
// ===== Thruster/Devices Functions =====
@@ -329,6 +354,14 @@ void devicesDCMessageCallback(const std_msgs::Int32& msg) {
329
354
devices_new[6 ] = msg.data ;
330
355
}
331
356
357
+ void statusMessageCallback (const std_msgs::String& msg) {
358
+ status_new = msg.data ;
359
+ updateStatusDisplay (status_new);
360
+
361
+ }
362
+
363
+
364
+
332
365
// ===== ROS Subscribers =====
333
366
ros::Subscriber<std_msgs::Int32> sub_tether (" /tether/status" , &tetherStatusMessageCallback);
334
367
ros::Subscriber<std_msgs::Float32> BATT1 (" /power/batteries/voltage/1" , &battery1Callback);
@@ -341,6 +374,7 @@ ros::Subscriber<std_msgs::Int32> DEVICEHYD("/sensors/hydrophones/status", &devic
341
374
ros::Subscriber<std_msgs::Int32> DEVICEACT (" /sensors/actuator/status" , &devicesACTMessageCallback);
342
375
ros::Subscriber<std_msgs::Int32> DEVICEFC (" /sensors/front_camera/status" , &devicesFCMessageCallback);
343
376
ros::Subscriber<std_msgs::Int32> DEVICEDC (" /sensors/down_camera/status" , &devicesDCMessageCallback);
377
+ ros::Subscriber<std_msgs::String> STATUS_SUB (" /mission_display" , &statusMessageCallback);
344
378
345
379
void thrusters (int T1, int T2, int T3, int T4, int T5, int T6, int T7, int T8) {
346
380
if (isInDryTestMode) return ;
@@ -527,6 +561,10 @@ void initMainPage() {
527
561
tft.print (btn.label );
528
562
}
529
563
}
564
+
565
+ // add this line right after the loop to show the surprise
566
+ updateStatusDisplay (status_new);
567
+
530
568
// Force battery display refresh after page change
531
569
voltages_old[0 ] = -1 ; // Force batt1 to update
532
570
voltages_old[1 ] = -1 ; // Force batt2 to update
@@ -616,6 +654,7 @@ void display_setup() {
616
654
nh.subscribe (DEVICEACT);
617
655
nh.subscribe (DEVICEFC);
618
656
nh.subscribe (DEVICEDC);
657
+ nh.subscribe (STATUS_SUB);
619
658
620
659
nh.advertise (DEPTH);
621
660
nh.advertise (pub);
0 commit comments