Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rtl button #28

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
import 'package:dart_mavlink/dialects/common.dart';

/// Constructs a MissionItem command to return to launch using MAV_CMD_NAV_RETURN_TO_LAUNCH (20).
///
/// @sequence The sequence number for the MAVLink frame.
/// @systemId The MAVLink system ID of the vehicle (normally "1").
/// @componentId The MAVLink component ID (normally "0").
/// @latitude The latitude of the launchpad (Defaults to where it was armed).
/// @longitude The longitude of the launchpad (Defaults to where it was armed).
/// @altitude The altitude of the waypoint (Defaults to 15m)
/// @param1 Unused
/// @param2 Unused
/// @param3 Unused
/// @param4 Unused
///
/// @return A MissionItem representing the reutrn to launch command.

MissionItem returnToLaunch(int sequence, int systemID, int componentID,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, I didn't read the docs when I approved this. You need to use a Command Long for this, check set_mode_constructor.dart, that should be similar.

{double latitude = 0.0,
double longitude = 0.0,
double altitude = 15.0,
double param1 = 0,
double param2 = 0,
double param3 = 0,
double param4 = 0}) {
var missionItem = MissionItem(
targetSystem: systemID,
targetComponent: componentID,
seq: sequence,
frame: mavFrameGlobalRelativeAlt,
command: mavCmdNavReturnToLaunch,
current: 1,
autocontinue: 1,
param1: param1,
param2: param2,
param3: param3,
param4: param4,
x: latitude,
y: longitude,
z: altitude,
missionType: 0);
return missionItem;
}
32 changes: 32 additions & 0 deletions flutter_app/lib/modules/return_to_launch.dart
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
import 'package:dart_mavlink/dialects/common.dart';
import 'package:dart_mavlink/mavlink.dart';
import 'package:imacs/modules/mavlink_communication.dart';
import 'dart:developer';

const String moduleName = "Return To Launch";

class ReturnToLaunch {
final MavlinkCommunication comm;
final MissionItem returnToLaunchConstructor;

// Requires both the constructor (Mission Item) and comm
ReturnToLaunch({required this.comm, required this.returnToLaunchConstructor});
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can call the command constructor within the module (look at change_drone_mode for an example)


// Skips the queues and forces the drone to return
void returnNoQueue() async {
if (comm.connectionType == MavlinkCommunicationType.tcp) {
await comm.tcpSocketInitializationFlag.future;
}

var frame = MavlinkFrame.v2(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This part should be done in the command constructor

returnToLaunchConstructor.seq,
returnToLaunchConstructor.targetSystem,
returnToLaunchConstructor.targetComponent,
returnToLaunchConstructor);

comm.sequence++;
comm.write(frame);

log('[$moduleName] Returning to Launch');
}
}
20 changes: 20 additions & 0 deletions flutter_app/lib/widgets/return_to_launch_widget.dart
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
import 'package:flutter/material.dart';
import 'package:imacs/modules/return_to_launch.dart';

class ReturnToLaunchButton extends StatelessWidget {
final ReturnToLaunch returnToLaunchCommand;

// Needs the ReturnToLaunch object from the return_to_launch dart
const ReturnToLaunchButton({Key? key, required this.returnToLaunchCommand})
: super(key: key);

// Returns a button that tells the drone to return to launch
@override
Widget build(BuildContext context) {
return ElevatedButton(
onPressed: () {
returnToLaunchCommand.returnNoQueue();
},
child: const Text("Return To Launch"));
}
}
40 changes: 40 additions & 0 deletions flutter_app/test/unit/return_to_launch_constructor_test.dart
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
import 'package:dart_mavlink/dialects/common.dart';
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

lgtm!

import 'package:dart_mavlink/mavlink.dart';
import 'package:imacs/command_constructors/return_to_launch_constructor.dart';
import 'package:test/test.dart';

void main() {
/// dialect: Selected MAVLink dialect
/// sequence: The sequence number for the MAVLink frame.
/// Each component counts up its send sequence.
/// Allows to detect packet loss.
/// systemId: The MAVLink system ID of the vehicle (normally "1").
/// componentId: The MAVLink component ID (normally "0").
var dialect = MavlinkDialectCommon();
const sequence = 0;
const systemID = 1;
const componentID = 0;

test("Return To Launch", () {
const createReturnToLaunchCommandNumber = mavCmdNavReturnToLaunch;
const latitude = 47.938;
const longitude = 8.545;
const altitude = 15.0;

var parser = MavlinkParser(dialect);
parser.stream.listen((MavlinkFrame frm) {
if (frm.message is MissionItem) {
var mi = frm.message as MissionItem;
expect(mi.command, equals(createReturnToLaunchCommandNumber));
expect(mi.x, equals(latitude));
expect(mi.y, equals(longitude));
expect(mi.z, equals(altitude));
}
});

var returnToLaunchCommand = returnToLaunch(sequence, systemID, componentID,
latitude: latitude, longitude: longitude, altitude: altitude);

parser.parse(returnToLaunchCommand.serialize().buffer.asUint8List());
});
}
32 changes: 32 additions & 0 deletions flutter_app/test/widget/return_to_launch_widget_test.dart
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
import 'package:flutter/material.dart';
import 'package:flutter_test/flutter_test.dart';
import 'package:imacs/modules/mavlink_communication.dart';
import 'package:imacs/modules/return_to_launch.dart';
import 'package:imacs/command_constructors/return_to_launch_constructor.dart';
import 'package:imacs/widgets/return_to_launch_widget.dart';

void main() {
group("Return to Launch Widget", () {
testWidgets("Return to Launch Button Generate",
(WidgetTester tester) async {
final mavlinkCommunication = MavlinkCommunication(
MavlinkCommunicationType.tcp, '127.0.0.1', 14550);
final ReturnToLaunch command = ReturnToLaunch(
comm: mavlinkCommunication,
returnToLaunchConstructor: returnToLaunch(0, 1, 0));

// Tests to see if the button renders
await tester.pumpWidget(MaterialApp(
home: Scaffold(
body: ReturnToLaunchButton(returnToLaunchCommand: command))));

// Waits for all frames and animations to settle
await tester.pumpAndSettle();

expect(find.byType(ElevatedButton), findsOneWidget);
expect(find.text("Return To Launch"), findsOneWidget);
});

testWidgets("Button sends MavLink command", (WidgetTester tester) async {});
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you need help with this test lmk

});
}