Skip to content

Commit

Permalink
First commit
Browse files Browse the repository at this point in the history
  • Loading branch information
BorealisJames committed Apr 21, 2023
0 parents commit e2816bd
Show file tree
Hide file tree
Showing 374 changed files with 144,100 additions and 0 deletions.
57 changes: 57 additions & 0 deletions HTTP.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
## MavESP8266
### MavESP8266 Web Interface

#### API

The idea is to have some sort of web interface so you can check the status and change parameters. While that is not done, there are however, a few URLs that can be used. Obviously, you need to be connected to the WiFi Bridge's Access Point for these URLs to work.

##### Get Parameters

http://192.168.4.1/getparameters

This will show the current parameters and their values.

##### Get Status

http://192.168.4.1/getstatus

This will show the current comm link status.

##### Set Parameters

http://192.168.4.1/setparameters?key=value&key=value

This will allow you to set any parameter to the specified value. Once set, the values are stored in non volatile memory (EEPROM) but will only take effect once you reboot it. Use this with caution as you may lock yourself out. For instance, if you change the AP password and don't remember later, currently you must either trigger the reset pin (see README) or reflash the module in order to revert the parameters. Also note that there is no validation done to the values entered.

There are the supported parameters:

| Key | Default Value | Description | Example |
| ------------- | -------------- | -------------- | -------------- |
| baud | 921600 | UAS UART Link Baud Rate | http://192.168.4.1/setparameters?baud=921600 |
| channel | 11 | AP WiFi Channel | http://192.168.4.1/setparameters?channel=11 |
| cport | 14555 | Local UDP Port | http://192.168.4.1/setparameters?cport=14555 |
| debug | 0 | Enable Debug Messages | http://192.168.4.1/setparameters?debug=0 |
| hport | 14550 | GCS UDP Port | http://192.168.4.1/setparameters?hport=14550 |
| mode | 0 | Set to AP Mode (0) or Station Mode (1) | http://192.168.4.1/setparameters?mode=1 |
| pwd | pixracer | WiFi AP Password | http://192.168.4.1/setparameters?pwd=pixracer |
| pwdsta | PixRacer | WiFi STA Password | http://192.168.4.1/setparameters?pwdsta=PixRacer |
| reboot | 0 | Reboot the WiFi Bridge | http://192.168.4.1/setparameters?reboot=1 |
| ssid | PixRacer | WiFi AP SSID | http://192.168.4.1/setparameters?ssid=PixRacer |
| ssidsta | PixRacer | WiFi STA SSID | http://192.168.4.1/setparameters?ssidsta=PixRacer |
| ipsta | 0.0.0.0 | Wifi STA Static IP | http://192.168.4.1/setparameters?ipsta=192.168.4.2 |
| gatewaysta | 0.0.0.0 | Wifi STA Gateway | http://192.168.4.1/setparameters?gatewaysta=192.168.4.1 |
| subnetsta | 0.0.0.0 | Wifi STA Subnet | http://192.168.4.1/setparameters?subnetsta=255.255.255.0 |

You can combine any number of parameters into one request. For example:

http://192.168.4.1/setparameters?baud=921600&channel=9&reboot=1

To connect to a typical existing network with a static ip:

http://192.168.4.1/setparameters?mode=1&ssidsta=networkname&pwdsta=thepassword&ipsta=192.168.1.123&gatewaysta=192.168.1.1&subnetsta=255.255.255.0

##### Upload New Firmware

http://192.168.4.1/update

This will bring up a simple page with a button to allow you to pick the new ```firmware.bin``` file to upload and a button to upload it to the WiFi Bridge. Again, caution when using this as there is no validation yet.
33 changes: 33 additions & 0 deletions LICENSE.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
This software is licensed generally under a permissive 3-Clause BSD license. Contributions are required
to be made under the same license.
```
/****************************************************************************
*
* Copyright (c) 2015, 2016 Gus Grubba. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
```
71 changes: 71 additions & 0 deletions PARAMETERS.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
## MavESP8266
### Mavlink Paramaters and Messages supported by the MavESP8266 Firmware

#### Parameters

The MavESP8266 uses ```MAV_COMP_ID_UDP_BRIDGE``` (240) as its component id. It will process messages sent to this component id or messages sent to ```MAV_COMP_ID_ALL``` only.

##### MAVLINK_MSG_ID_PARAM_REQUEST_LIST

If this message is sent to *All Components* (```MAV_COMP_ID_ALL```), or specifically to the MavESP8266 component ID, it will return its list of parameters. Messages sent to ```MAV_COMP_ID_ALL``` will be forwarded to the UAS as well.

##### MAVLINK_MSG_ID_PARAM_REQUEST_READ

If this message is sent specifically to the MavESP8266 component ID, it will return the requested parameter (either by ID or by Index)

##### MAVLINK_MSG_ID_PARAM_SET

If this message is sent specifically to the MavESP8266 component ID, it will set the new value for the specified parameter. Note that this only sets the value for the current session. It does not write the values to EEPROM. See MAV_CMD_PREFLIGHT_STORAGE below.

#### Available Parameters

| Parameter ID | Parameter Type | Description |
| ------------- | -------------- | ----------- |
| DEBUG_ENABLED | MAV_PARAM_TYPE_INT8 | Enable Debug Messages (1) |
| SW_VER | MAV_PARAM_TYPE_UINT32 | Firmware Version (Read Only) |
| UART_BAUDRATE | MAV_PARAM_TYPE_UINT32 | UAS UART Link Baud Rate (default to 921600) |
| WIFI_CHANNEL | MAV_PARAM_TYPE_UINT32 | AP WiFi Channel (default to 11) |
| WIFI_IPADDRESS | MAV_PARAM_TYPE_UINT32 | Local IP Address (default to 192.168.4.1 when in AP Mode) (Read Only) |
| WIFI_MODE | MAV_PARAM_TYPE_INT8 | WiFi Operating Mode (3) |
| WIFI_PASSWORD1 | MAV_PARAM_TYPE_UINT32 | WiFi AP Password (2) |
| WIFI_PASSWORD2 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_PASSWORD3 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_PASSWORD4 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_PWDSTA1 | MAV_PARAM_TYPE_UINT32 | WiFi STA Password (2) |
| WIFI_PWDSTA2 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_PWDSTA3 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_PWDSTA4 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSID1 | MAV_PARAM_TYPE_UINT32 | WiFi AP SSID (2) |
| WIFI_SSID2 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSID3 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSID4 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSIDSTA1 | MAV_PARAM_TYPE_UINT32 | WiFi STA SSID (2) |
| WIFI_SSIDSTA2 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSIDSTA3 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_SSIDSTA4 | MAV_PARAM_TYPE_UINT32 | |
| WIFI_IPSTA | MAV_PARAM_TYPE_UINT32 | Wifi STA Static IP Address (4) |
| WIFI_GATEWAYSTA | MAV_PARAM_TYPE_UINT32 | Wifi STA Gateway Address (4) |
| WIFI_SUBNETSTA | MAV_PARAM_TYPE_UINT32 | Wifi STA Subnet Address (4) |
| WIFI_UDP_CPORT | MAV_PARAM_TYPE_UINT16 | Local UDP Port (default to 14555) |
| WIFI_UDP_HPORT | MAV_PARAM_TYPE_UINT16 | GCS UDP Port (default to 14550) |

##### Notes

* (1) If debug is enabled, debug messages are sent using ```MAVLINK_MSG_ID_STATUSTEXT``` with a proper ```MAV_SEVERITY_DEBUG``` type. Other messages types, ```MAV_SEVERITY_NOTICE``` for example, are sent regardless.
* (2) MavLink parameter messages only support a 32-Bit parameter (be it a float, an uint32_t, etc.) In other to fit a 16-character SSID and a 16-character Password, 4 paramaters are used for each. The 32-Bit storage is used to contain 4 bytes for the string.
* (3) The mode defaults to 0. Set to 0 to act as an Access Point. Set to 1 to connect to an existing WiFi network using the STA (Station Mode) SSID and password. When in *Station Mode*, the module will attempt to connect for up to one minute. If after that it cannot connect, it reverts to AP mode.
* (4) Defaults to 0 for an unset address. If either the STA IP, Gateway, or Subnet are set, then all three need to be set for it to work properly.

#### MAVLINK_MSG_ID_COMMAND_LONG

In addition to parameters, MavESP8266 also supports a few commands, which will be handled _**if addressed to its component ID**_:

##### MAV_CMD_PREFLIGHT_STORAGE

* If ```param1``` == 0 It will load all parameters from EEPROM overwriting any changes.
* If ```param1``` == 1 It will save all current parameters to EEPROM.
* If ```param1``` == 2 It will reset all parameters to the original default values. Note that it will not store them to EEPROM. You must request that separately if that's what you want to do.

##### MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN

* If ```param2``` == 1 It will cause the ESP8266 module to reboot. This is necessary if you want parameter changes to take effect. Out of the above, the only parameter that takes effect immediatly upon changing is **DEBUG_ENABLED**. All other values will only take effect at boot time.
68 changes: 68 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
# MavESP8266

## Current Binary

Download the current version (MAVLink V2) from here: [Firmware version 1.2.2](http://www.grubba.com/mavesp8266/firmware-1.2.2.bin)

Download the legacy version (MAVLink V1) from here: [Firmware version 1.1.1](http://www.grubba.com/mavesp8266/firmware-1.1.1.bin)

## ESP8266 WiFi Access Point and MavLink Bridge

[![Join the chat at https://gitter.im/dogmaphobic/mavesp8266](https://badges.gitter.im/dogmaphobic/mavesp8266.svg)](https://gitter.im/dogmaphobic/mavesp8266?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)

This was developed using a [NodeMCU v2 Dev Kit](http://www.seeedstudio.com/depot/NodeMCU-v2-Lua-based-ESP8266-development-kit-p-2415.html) as it conveniently provides a secondary UART for debugging. It has been tested with the ESP-01 shipped with the [PixRacer](https://pixhawk.org/modules/pixracer) and it is stable at 921600 baud.

The build enviroment is based on [PlatformIO](http://platformio.org). Follow the instructions found here: http://platformio.org/#!/get-started (only tested on Mac OS) for installing it but skip the ```platform init``` step as this has already been done, modified and it is included in this repository. In summary:

```
brew install platformio
git clone --recursive https://github.com/dogmaphobic/mavesp8266.git
cd mavesp8266
platformio run
```

When you run ```platformio run``` for the first time, it will download the toolchains and all necessary libraries automatically.

### Useful commands: ESP32-WROOM

* ```platformio run -e espwroom32 -t upload```

### Useful commands: ESP12e

* ```platformio run``` - process/build all targets
* ```platformio run -e esp12e``` - process/build just the ESP12e target (the NodeMcu v2, Adafruit HUZZAH, etc.)
* ```platformio run -e esp12e -t upload``` - build and upload firmware to embedded board
* ```platformio run -t clean``` - clean project (remove compiled files)

### Useful commands: ESP-01
* ```platformio run``` - process/build all targets
* ```platformio run -e esp01_1m``` - process/build just the ESP01 target with 1MB [Amazon](https://www.amazon.com/gp/product/B01EA3UJJ4)
* ```platformio run -e esp01_1m -t upload``` - build and upload firmware to embedded board
* ```platformio run -t clean``` - clean project (remove compiled files)



The resulting image(s) can be found in the directory ```.pioenvs``` created during the build process.

### MavLink Submodule

The ```git clone --recursive``` above not only cloned the MavESP8266 repository but it also installed the dependent [MavLink](https://github.com/mavlink/c_library) sub-module. To upated the module (when needed), use the command:

```git submodule update --init```

### Wiring it up

User level (as well as wiring) instructions can be found [here for px4](https://docs.px4.io/en/telemetry/esp8266_wifi_module.html) and [here for ArduPilot](http://ardupilot.org/copter/docs/common-esp8266-telemetry.html)

* Resetting to Defaults: In case you change the parameters and get locked out of the module, all the parameters can be reset by bringing the GPIO02 pin low (Connect GPIO02 pin to GND pin).

Get the ESP-01 adapter board here on [Amazon](https://www.amazon.com/gp/product/B07Q17XJ36/); commonly called an "ESP01 programmer", this one has a little rocker switch on the side (UART side for serial TTL debugging by AT commands, PROG for firmware programming) and a yellow pin header which allows you plugin the ESP01 module without any wires. It defaults to 115200 and enumerates under Ubuntu as a ch341-uart converter.


### MavLink Protocol

The MavESP8266 handles its own set of parameters and commands. Look at the [PARAMETERS](PARAMETERS.md) page for more information.

### HTTP Protocol

There are some preliminary URLs that can be used for checking the WiFi Bridge status as well as updating firmware and changing parameters. [You can find it here.](HTTP.md)
Loading

0 comments on commit e2816bd

Please sign in to comment.