Skip to content
This repository was archived by the owner on Jul 25, 2022. It is now read-only.

Commit 2ff4ef1

Browse files
committed
Moved files to src/ directory for recursive build.
See arduino/arduino-builder#148
1 parent 0650130 commit 2ff4ef1

25 files changed

+173
-0
lines changed
+145
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,145 @@
1+
#include "main.hpp"
2+
#include "board.hpp"
3+
#include "Drives.hpp"
4+
#include "wifi_ap.hpp"
5+
#include "WebserverHandle.hpp"
6+
#include "utils/array.hpp"
7+
#include <assert.h>
8+
#include <ESP8266WebServer.h>
9+
#include <algorithm>
10+
#include <functional>
11+
12+
static EnvironmentRecord environmentRecord;
13+
static ESP8266WebServer server(80);
14+
static WebserverHandle webserverHandle(server, environmentRecord);
15+
16+
void main::setup()
17+
{
18+
Serial.begin(115200);
19+
delay(100);
20+
Serial.flush();
21+
delay(100);
22+
Serial.printf("\n begin program '%s'\n", __FILE__);
23+
Wire.begin(board::sda, board::scl);
24+
board::ioExpander1.init();
25+
board::ioExpander1.interruptMode(MCP23017InterruptMode::Separated);
26+
board::ioExpander1.interrupt(MCP23017Port::B, FALLING);
27+
28+
// initialize pins
29+
pinMode(board::debugLed, OUTPUT);
30+
digitalWrite(board::debugLed, LOW);
31+
pinMode(board::ioExpanderIntB, INPUT_PULLUP);
32+
pinMode(board::ioExpanderIntAInv, INPUT);
33+
pinMode(board::VL53L1_1_INT, INPUT_PULLUP);
34+
pinMode(board::VL53L1_2_INT, INPUT_PULLUP);
35+
pinMode(board::VL53L1_3_INT, INPUT_PULLUP);
36+
pinMode(board::VL53L1_4_INT, INPUT_PULLUP);
37+
pinMode(board::leftBumper, INPUT_PULLUP);
38+
pinMode(board::rightBumper, INPUT_PULLUP);
39+
40+
drives::LeftDrive::init();
41+
drives::RightDrive::init();
42+
43+
// initialize distance measurement sensors
44+
for(std::size_t i=0; i<size(board::distanceSensors); i++)
45+
{
46+
board::distanceSensors[i]->begin();
47+
board::distanceSensors[i]->VL53L1_Off();
48+
}
49+
for(std::size_t i=0; i<size(board::distanceSensors); i++)
50+
{
51+
Serial.printf("Initialize distance sensor %u...", i);
52+
assert(board::distanceSensors[i]->initSensorWithAddressValue(VL53L1GpioInterface::defaultAddressValue + 1 + i) == VL53L1_ERROR_NONE);
53+
Serial.printf("Done.\n");
54+
}
55+
for(std::size_t i=0; i<size(board::distanceSensors); i++)
56+
{
57+
board::distanceSensors[i]->VL53L1_SetPresetMode(VL53L1_PRESETMODE_RANGING);
58+
board::distanceSensors[i]->VL53L1_ClearInterruptAndStartMeasurement();
59+
}
60+
61+
attachInterrupt(board::ioExpanderIntB, drives::stopDrives, FALLING);
62+
63+
Serial.printf("connect to wifi %s ", ssid);
64+
WiFi.begin(ssid, password);
65+
while (WiFi.status() != WL_CONNECTED)
66+
{
67+
delay(500);
68+
Serial.print(".");
69+
}
70+
Serial.println(" connected");
71+
72+
server.begin();
73+
Serial.printf("webserver has IP %s\n", WiFi.localIP().toString().c_str());
74+
server.on("/", std::bind(&WebserverHandle::handleRoot, &webserverHandle));
75+
webserverHandle.setup();
76+
}
77+
78+
static void printSensorStatus(VL53L1GpioInterface* const sensor)
79+
{
80+
VL53L1_MultiRangingData_t MultiRangingData;
81+
VL53L1_MultiRangingData_t *pMultiRangingData = &MultiRangingData;
82+
uint8_t NewDataReady = 0;
83+
int status;
84+
85+
status = sensor->VL53L1_GetMeasurementDataReady(&NewDataReady);
86+
87+
if((!status)&&(NewDataReady!=0))
88+
{
89+
status = sensor->VL53L1_GetMultiRangingData(pMultiRangingData);
90+
const std::uint8_t no_of_object_found=pMultiRangingData->NumberOfObjectsFound;
91+
Serial.printf("VL53L1 Satellite @ %#hhx: Status=%3i, \tCount=%3hhu, \t#Objs=%3hhu", sensor->VL53L1_GetDeviceAddressValue(), status, pMultiRangingData->StreamCount, no_of_object_found);
92+
if(status == VL53L1_ERROR_NONE)
93+
{
94+
for(std::uint8_t j=0;j<std::min(no_of_object_found, static_cast<std::uint8_t>(VL53L1_MAX_RANGE_RESULTS));j++)
95+
{
96+
Serial.print("\r\n ");
97+
Serial.print("status=");
98+
Serial.print(pMultiRangingData->RangeData[j].RangeStatus);
99+
Serial.print(", D=");
100+
Serial.print(pMultiRangingData->RangeData[j].RangeMilliMeter);
101+
Serial.print("mm");
102+
Serial.print(", Signal=");
103+
Serial.print((float)pMultiRangingData->RangeData[j].SignalRateRtnMegaCps/65536.0);
104+
Serial.print(" Mcps, Ambient=");
105+
Serial.print((float)pMultiRangingData->RangeData[j].AmbientRateRtnMegaCps/65536.0);
106+
Serial.print(" Mcps");
107+
}
108+
status = sensor->VL53L1_ClearInterruptAndStartMeasurement();
109+
}
110+
Serial.println("");
111+
}
112+
}
113+
114+
void main::loop()
115+
{
116+
for(std::size_t i=0; i<size(board::distanceSensors); ++i)
117+
{
118+
printSensorStatus(board::distanceSensors[i]);
119+
}
120+
server.handleClient();
121+
//Serial.printf("left: \t%3u, right: \t%3u\n", drives::LeftDrive::counter, drives::RightDrive::counter);
122+
if(drives::LeftDrive::isIdle && drives::RightDrive::isIdle)
123+
{
124+
const Position newPositionCandidate = drives::flushCurrentPosition();
125+
if(environmentRecord.positions[environmentRecord.positionIndex] != newPositionCandidate)
126+
{
127+
environmentRecord.positions[++environmentRecord.positionIndex] = newPositionCandidate;
128+
environmentRecord.positionIndex %= environmentRecord.numberOfPositions;
129+
webserverHandle.loop();
130+
}
131+
const auto newTarget = webserverHandle.flushTargetRequest();
132+
if(newTarget.isTargetNew)
133+
{
134+
const bool bumperIsPressed = digitalRead(board::leftBumper) == LOW || digitalRead(board::rightBumper) == LOW;
135+
if(newTarget.newDrive!=0 && (!newTarget.forward || !bumperIsPressed))
136+
{
137+
drives::driveCounter(newTarget.newDrive, drives::cruiseSpeed, !newTarget.forward);
138+
}
139+
else if(newTarget.newRotate!=0 && !bumperIsPressed)
140+
{
141+
drives::rotateCounter(newTarget.newRotate, drives::cruiseSpeed, newTarget.clockwise);
142+
}
143+
}
144+
}
145+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
#ifndef APPLICATION_MAIN_HPP_
2+
#define APPLICATION_MAIN_HPP_
3+
4+
5+
6+
7+
8+
#endif /* APPLICATION_MAIN_HPP_ */
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
#ifndef UTILS_ARDUINO_HELPERS_HPP_
2+
#define UTILS_ARDUINO_HELPERS_HPP_
3+
4+
#include <Arduino.h>
5+
6+
using Milliseconds = decltype(millis());
7+
8+
#endif /* UTILS_ARDUINO_HELPERS_HPP_ */
+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
#ifndef UTILS_NUMBERS_HPP_
2+
#define UTILS_NUMBERS_HPP_
3+
4+
#include <math.h>
5+
6+
namespace numbers
7+
{
8+
inline constexpr double pi = M_PI;
9+
}
10+
11+
12+
#endif /* UTILS_NUMBERS_HPP_ */

0 commit comments

Comments
 (0)