diff --git a/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino b/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino new file mode 100644 index 0000000000..ec822deef2 --- /dev/null +++ b/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino @@ -0,0 +1,336 @@ +#include +#include + +#include +#include + +/*//#include */ +#include "C:\Users\rmackay9\Documents\GitHub\ardupilot\Build.ArduCopter\libraries\GCS_MAVLink\include\mavlink\v2.0\common\mavlink.h" +#include +#include +/*#include // download from https://github.com/PaulStoffregen/Time */ +//#include "C:\Users\rmackay9\Documents\GitHub\Time\Time.h" + +////////////////// Pozyx Prams ////////////////////////////// + +#define NUM_ANCHORS 4 +// the network id of the anchors: change these to the network ids of your anchors. +uint16_t anchors[4] = { 0x601C, // (0,0) + 0x6020, // x-axis + 0x6057, // y-axis + 0x605E}; + +// only required for manual anchor calibration. +// Please change this to the coordinates measured for the anchors +int32_t anchors_x[NUM_ANCHORS] = {0, 18600, 0, 18600}; // anchor x-coorindates in mm (horizontal) +int32_t anchors_y[NUM_ANCHORS] = {0, 0, 10000, 10000}; // anchor y-coordinates in mm (vertical) +int32_t heights[NUM_ANCHORS] = {1420, 0, 0, 1450}; // anchor z-coordinates in mm + +////////////////// MAVLINK Prams ////////////////////////////// +#define LATITUDE_BASE (36.324187 * 1.0e7) +#define LONGITUDE_BASE (138.639212 * 1.0e7) +uint8_t buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; +int32_t latitude = 0; +int32_t longitude = 0; + +// RX TX serial for flight controller ex) Pixhawk +// https://github.com/PaulStoffregen/AltSoftSerial + +SoftwareSerial fcboardSerial(10, 11); // rx, tx + +//////////////////////////////////////////////// + +void setup() +{ + Serial.begin(115200); + fcboardSerial.begin(57600); + + if (Pozyx.begin() == POZYX_FAILURE) { + Serial.println(("ERR: shield")); + delay(100); + abort(); + } + + Serial.println(("V1.0")); + + // clear all previous devices in the device list + Pozyx.clearDevices(); + + //int status = Pozyx.doAnchorCalibration(POZYX_2_5D, 10, num_anchors, anchors, heights); + /*int status = Pozyx.doAnchorCalibration(POZYX_2D, 10, num_anchors, anchors, heights); + if (status != POZYX_SUCCESS) { + Serial.println(status); + Serial.println(("ERROR: calibration")); + Serial.println(("Reset required")); + delay(100); + abort(); + }*/ + + // if the automatic anchor calibration is unsuccessful, try manually setting the anchor coordinates. + // fot this, you must update the arrays anchors_x, anchors_y and heights above + // comment out the doAnchorCalibration block and the if-statement above if you are using manual mode + SetAnchorsManual(); + + printCalibrationResult(); + Serial.println(("Waiting..")); + delay(5000); + + Serial.println(("Starting: ")); +} + +void loop() +{ + coordinates_t position; + + int status = Pozyx.doPositioning(&position, POZYX_2_5D, 1000); + //int status = Pozyx.doPositioning(&position); + + if (status == POZYX_SUCCESS) { + // print out the result + printCoordinates(position); + + // send GPS MAVLINK message + SendGPSMAVLinkMessage(position); + } else { + Serial.println("fail"); + } +} + +// function to print the coordinates to the serial monitor +void printCoordinates(coordinates_t coor) +{ + Serial.print("x:"); + Serial.print(coor.x); + print_tab(); + Serial.print("y:"); + Serial.print(coor.y); + print_tab(); + Serial.print("z:"); + Serial.print(coor.z); + print_tab(); + Serial.print("lat:"); + Serial.print(latitude); + print_tab(); + Serial.print("lng:"); + Serial.print(longitude); + print_tab(); + Serial.println(); +} + +void print_comma() +{ + Serial.print(","); +} + +void print_tab() +{ + Serial.print("\t"); +} + +#define LOCATION_SCALING_FACTOR_INV_MM 0.08983204953368922f +#define DEG_TO_RAD (M_PI / 180.0f) + +float longitude_scale(uint32_t lat) +{ + static int32_t last_lat = 0; + static float scale = 1.0; + if (labs(last_lat - lat) < 100000) { + // we are within 0.01 degrees (about 1km) of the + // previous latitude. We can avoid the cos() and return + // the same scale factor. + return scale; + } + scale = cosf(lat * 1.0e-7f * DEG_TO_RAD); + if (scale < 0.01f) { + scale = 0.01f; + } + if (scale > 1.0f) { + scale = 1.0f; + } + last_lat = lat; + return scale; +} + +void location_offset(int32_t &lat, int32_t &lng, int32_t offset_north_mm, int32_t offset_east_mm) +{ + int32_t dlat = offset_north_mm * LOCATION_SCALING_FACTOR_INV_MM; + int32_t dlng = (offset_east_mm * LOCATION_SCALING_FACTOR_INV_MM) / longitude_scale(lat); + lat += dlat; + lng += dlng; +} + +// print out the anchor coordinates (also required for the processing sketch) +void printCalibrationResult() +{ + uint8_t list_size; + int status; + + status = Pozyx.getDeviceListSize(&list_size); + Serial.print("list: "); + Serial.println(status*list_size); + + if (list_size == 0) { + Serial.println("Cal fail."); + Serial.println(Pozyx.getSystemError()); + return; + } + + uint16_t device_ids[list_size]; + status &= Pozyx.getDeviceIds(device_ids,list_size); + + Serial.println(("Cal:")); + Serial.print(("Anchors found: ")); + Serial.println(list_size); + + coordinates_t anchor_coor; + + for (int i=0; i= rmon) { + rmon += 12; + year -= 1; + } + + // get time in seconds since unix epoch + uint32_t ret = (year/4) - 15 + 367*rmon/12 + day; + ret += year*365 + 10501; + ret = ret*24 + hour; + ret = ret*60 + min; + ret = ret*60 + sec; + + // convert to time since GPS epoch + ret -= 272764785UL; + + // get GPS week and time + time_week = ret / (7*86400UL); + time_week_ms = (ret % (7*86400UL)) * 1000; + time_week_ms += msec; +} +