From 2d365dcffe0a44a1f08f761d1208d671424a9b52 Mon Sep 17 00:00:00 2001 From: Oleg Kalachev Date: Fri, 19 Jan 2024 05:14:12 +0300 Subject: [PATCH] Minor fixes --- docs/firmware.md | 2 +- flix/cli.ino | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/firmware.md b/docs/firmware.md index 47312b6..9c74c43 100644 --- a/docs/firmware.md +++ b/docs/firmware.md @@ -18,7 +18,7 @@ The main loop is running at 1000 Hz. All the dataflow is happening through globa Firmware source files are located in `flix` directory. The key files are: -* [`flix.ino`](../flix/flix.ino) — main entry point, Arduino sketch. Include global variables definition and the main loop. +* [`flix.ino`](../flix/flix.ino) — main entry point, Arduino sketch. Includes global variables definition and the main loop. * [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration. * [`rc.ino`](../flix/rc.ino) — reading data from the RC receiver, RC calibration. * [`estimate.ino`](../flix/estimate.ino) — drone's attitude estimation, complementary filter. diff --git a/flix/cli.ino b/flix/cli.ino index 3dd7d9e..3737eb9 100644 --- a/flix/cli.ino +++ b/flix/cli.ino @@ -30,7 +30,7 @@ const char* motd = "cr - calibrate RC\n" "cg - calibrate gyro\n" "ca - calibrate accel\n" -"fullmot - test motor on all signals\n" +"fullmot - full motor test\n" "reset - reset drone's state\n"; const struct Param {