Skip to content

Commit

Permalink
IMACS widget update to show data in a more user friendly manner (#14)
Browse files Browse the repository at this point in the history
* added gridview, changed UI 

* wrote tests for data fields
  • Loading branch information
TheFJcurve authored Jun 30, 2024
1 parent 7aa1060 commit 1fdd607
Show file tree
Hide file tree
Showing 6 changed files with 300 additions and 134 deletions.
12 changes: 6 additions & 6 deletions flutter_app/.metadata
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# This file should be version controlled and should not be manually edited.

version:
revision: "367f9ea16bfae1ca451b9cc27c1366870b187ae2"
revision: "a14f74ff3a1cbd521163c5f03d68113d50af93d3"
channel: "stable"

project_type: app
Expand All @@ -13,11 +13,11 @@ project_type: app
migration:
platforms:
- platform: root
create_revision: 367f9ea16bfae1ca451b9cc27c1366870b187ae2
base_revision: 367f9ea16bfae1ca451b9cc27c1366870b187ae2
- platform: windows
create_revision: 367f9ea16bfae1ca451b9cc27c1366870b187ae2
base_revision: 367f9ea16bfae1ca451b9cc27c1366870b187ae2
create_revision: a14f74ff3a1cbd521163c5f03d68113d50af93d3
base_revision: a14f74ff3a1cbd521163c5f03d68113d50af93d3
- platform: linux
create_revision: a14f74ff3a1cbd521163c5f03d68113d50af93d3
base_revision: a14f74ff3a1cbd521163c5f03d68113d50af93d3

# User provided section

Expand Down
49 changes: 32 additions & 17 deletions flutter_app/lib/data_field_widget.dart
Original file line number Diff line number Diff line change
Expand Up @@ -29,23 +29,38 @@ class DataField<T> extends StatelessWidget {

@override
Widget build(BuildContext context) {
return Row(children: [
Text(
"$name: ",
style: const TextStyle(
fontWeight: FontWeight.bold,
return Column(
mainAxisAlignment: MainAxisAlignment.center,
children: [
Text(
name,
style: const TextStyle(
fontWeight: FontWeight.bold,
),
textAlign: TextAlign.center,
),
),
StreamBuilder<T>(
stream: value,
builder: (context, snapshot) {
if (snapshot.hasData && snapshot.data != null) {
return Text(formatter(snapshot.data as T).toString());
} else {
return const Text('No data');
}
},
)
]);
const SizedBox(
height: 10,
),
StreamBuilder<T>(
stream: value,
builder: (context, snapshot) {
if (snapshot.hasData && snapshot.data != null) {
return Text(
formatter(snapshot.data as T).toString(),
style: const TextStyle(
fontSize: 38,
color: Colors.blue,
fontWeight: FontWeight.bold,
),
textAlign: TextAlign.center,
);
} else {
return const Text('No data');
}
},
),
],
);
}
}
79 changes: 79 additions & 0 deletions flutter_app/lib/drone_information.dart
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
import 'dart:math';
import 'package:flutter/material.dart';
import 'package:imacs/mavlink_communication.dart';

import 'data_field_widget.dart';

/// Widget to arrange multiple data widgets in tabular form.
///
/// This widget selective data made available by MavlinkCommunication.
/// Arranges the data in a grid with two columns and applies a border.
///
class DroneInformation extends StatelessWidget {
/// @brief Constructs a DroneInformation widget.
///
/// @param comm The communication channel (MAVLink) where to get
/// the data from
///
const DroneInformation({
super.key,
required this.comm,
});

final MavlinkCommunication comm;

@override
Widget build(BuildContext context) {
return Container(
decoration: BoxDecoration(
border: Border.all(
color: Colors.black,
),
),
child: GridView.count(
crossAxisCount: 2,

/// describes how many items in one row.
childAspectRatio: 2,

/// describes how spaced out things are.
children: <DataField>[
DataField<double>(
name: 'Yaw (deg)',
value: comm.getYawStream(),
formatter: (double value) =>
(value / pi * 180.0).toStringAsFixed(2),
),
DataField<double>(
name: 'Pitch (deg)',
value: comm.getPitchStream(),
formatter: (double value) =>
(value / pi * 180.0).toStringAsFixed(2),
),
DataField<double>(
name: 'Roll (deg)',
value: comm.getRollStream(),
formatter: (double value) =>
(value / pi * 180.0).toStringAsFixed(2),
),
// global position
DataField<int>(
name: 'Latitude',
value: comm.getLatStream(),
formatter: (int value) => (value / 1e7).toStringAsFixed(2),
),
DataField<int>(
name: 'Longitude',
value: comm.getLonStream(),
formatter: (int value) => (value / 1e7).toStringAsFixed(2),
),
DataField<int>(
name: 'Altitude (m)',
value: comm.getAltStream(),
formatter: (int value) => (value / 1e3).toStringAsFixed(2),
),
],
),
);
}
}
65 changes: 21 additions & 44 deletions flutter_app/lib/main.dart
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
import 'dart:math';

import 'package:flutter/material.dart';
import 'package:imacs/drone_information.dart';

import 'package:imacs/data_field_widget.dart';
import 'package:imacs/mavlink_communication.dart';

void main() async {
runApp(const App());
}

class App extends StatelessWidget {
const App({Key? key}) : super(key: key);
const App({
Key? key,
}) : super(key: key);

@override
Widget build(BuildContext context) {
Expand All @@ -24,55 +24,32 @@ class App extends StatelessWidget {
}
}

// HomePage contains the main app Title and DroneInformation Widget.
// DroneInformation is responsible for showing all the data fetched
// from Mission Planner MAVLink
class HomePage extends StatelessWidget {
HomePage({Key? key, required this.title}) : super(key: key);
HomePage({
Key? key,
required this.title,
}) : super(key: key);

final String title;
final comm =
MavlinkCommunication(MavlinkCommunicationType.tcp, '127.0.0.1', 14550);
final comm = MavlinkCommunication(
MavlinkCommunicationType.tcp,
'127.0.0.1',
14550,
);

@override
Widget build(BuildContext context) {
return Scaffold(
appBar: AppBar(
title: Text(title),
title: Center(child: Text(title)),
),
body: Column(
children: [
// attitude
DataField<double>(
name: 'Yaw (deg)',
value: comm.getYawStream(),
formatter: (double value) => (value / pi * 180.0).round(),
),
DataField<double>(
name: 'Pitch (deg)',
value: comm.getPitchStream(),
formatter: (double value) => (value / pi * 180.0).round(),
),
DataField<double>(
name: 'Roll (deg)',
value: comm.getRollStream(),
formatter: (double value) => (value / pi * 180.0).round(),
),

// global position
DataField<int>(
name: 'Latitude',
value: comm.getLatStream(),
formatter: (int value) => (value / 1e7).round(),
),
DataField<int>(
name: 'Longitude',
value: comm.getLonStream(),
formatter: (int value) => (value / 1e7).round(),
),
DataField<int>(
name: 'Altitude (m)',
value: comm.getAltStream(),
formatter: (int value) => (value / 1e3).round(),
),
],
body: SizedBox(
width: 500,
height: 400,
child: DroneInformation(comm: comm),
),
);
}
Expand Down
Loading

0 comments on commit 1fdd607

Please sign in to comment.