Skip to content

Commit 7b8ca13

Browse files
App structure redesign (#408)
* Create modules skeleton for new app structure (#382) * Add modules and main.cpp skeleton * Fix typos * Create watchdog module (#389) * Watchdog module * clang fix * clang fix2 * test-watchdog * Edited WatchdogWrapper.h * Fixed pure virtual function errors * fixed namespace error * Fixed error2 * Cmake * Cmake * Cmake fix * Top-level Cmake * Changes made * clang fix * Update libs/utility/src/WatchdogWrapper.cpp Co-authored-by: Cindy Li <cindyli0213@hotmail.com> * Update test-apps/test-watchdog/src/main.cpp Co-authored-by: Cindy Li <cindyli0213@hotmail.com> * cmake * Changed periodic function name * watchdogwrapper fix Co-authored-by: Cindy Li <cindyli0213@hotmail.com> * Create PDB monitoring module (#392) * PDB Module added * CMake * rename include * Fixed Errors * clang fix * Changes made * Made pins config private members * clang * fix folder structure * fix common modules not found * rebase master * Address pr comments Co-authored-by: jahnavithota2011 <34670246+jahnavithota2011@users.noreply.github.com>
1 parent ccc1364 commit 7b8ca13

File tree

20 files changed

+471
-28
lines changed

20 files changed

+471
-28
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,7 @@ function(add_app_subdirectory APP_SUBDIRECTORY)
8989
endfunction()
9090

9191
## Include Rover Apps
92+
add_subdirectory(${ROVER_APPS_DIR}/common)
9293
add_app_subdirectory(${ROVER_APPS_DIR}/arm_2021)
9394
add_app_subdirectory(${ROVER_APPS_DIR}/gamepad_2021)
9495
add_app_subdirectory(${ROVER_APPS_DIR}/gimbal_2021)

libs/utility/include/WatchdogWrapper.h

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,8 @@ namespace Utility {
55

66
class WatchdogWrapper {
77
public:
8-
static void startWatchdog(std::chrono::milliseconds countdown_ms = 5000ms, std::chrono::milliseconds pet_ms = 1000ms);
9-
static void logResetReason();
10-
11-
private:
12-
static void petWatchdog(std::chrono::milliseconds *pet_ms);
13-
static Thread pet_thread;
8+
static void startWatchdog(std::chrono::milliseconds countdown_ms);
9+
static void logResetReason(void);
10+
static void petWatchdog(void);
1411
};
1512
} // namespace Utility

libs/utility/src/WatchdogWrapper.cpp

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -6,17 +6,13 @@
66

77
namespace Utility {
88

9-
Thread WatchdogWrapper::pet_thread;
10-
11-
void WatchdogWrapper::startWatchdog(std::chrono::milliseconds countdown_ms /*= 5000ms*/,
12-
std::chrono::milliseconds pet_ms /*= 1000ms*/) {
9+
void WatchdogWrapper::startWatchdog(std::chrono::milliseconds countdown_ms) {
1310
uint32_t countdown_uint32 = countdown_ms.count();
1411
Watchdog &watchdog = Watchdog::get_instance();
1512
watchdog.start(countdown_uint32);
16-
pet_thread.start(callback(WatchdogWrapper::petWatchdog, &pet_ms));
1713
}
1814

19-
void WatchdogWrapper::logResetReason() {
15+
void WatchdogWrapper::logResetReason(void) {
2016
const reset_reason_t reason = ResetReason::get();
2117
if (reason == RESET_REASON_WATCHDOG) {
2218
time_t seconds = time(NULL);
@@ -26,10 +22,7 @@ void WatchdogWrapper::logResetReason() {
2622
}
2723
}
2824

29-
void WatchdogWrapper::petWatchdog(std::chrono::milliseconds *pet_ms) {
30-
while (1) {
31-
Watchdog::get_instance().kick();
32-
ThisThread::sleep_for(*pet_ms);
33-
}
25+
void WatchdogWrapper::petWatchdog(void) {
26+
Watchdog::get_instance().kick();
3427
}
35-
} // namespace Utility
28+
} // namespace Utility

rover-apps/arm_2021/CMakeLists.txt

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
add_executable(arm_2021)
2-
target_sources(arm_2021 PRIVATE src/main.cpp)
3-
target_include_directories(arm_2021 PUBLIC include)
2+
target_sources(arm_2021 PRIVATE ${ROVER_APPS_DIR}/common/src/main.cpp)
3+
target_include_directories(arm_2021 PUBLIC include ${ROVER_APPS_DIR}/common/include)
44
target_link_libraries(arm_2021
55
PRIVATE
66
#Control
@@ -21,6 +21,8 @@ target_link_libraries(arm_2021
2121
CANMsg
2222
#Sensor
2323
CurrentSensor
24+
#common-modules
25+
WatchdogModule
2426
#Other
2527
uwrt-mars-rover-hw-bridge
2628
Logger
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
#pragma once
2+
3+
#include <vector>
4+
5+
#include "Module.h"
6+
#include "WatchdogModule.h"
7+
8+
WatchdogModule arm_watchdog;
9+
10+
std::vector<Module*> gModules = {
11+
&arm_watchdog,
12+
};

rover-apps/common/CMakeLists.txt

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
add_library(WatchdogModule STATIC)
2+
target_sources(WatchdogModule PRIVATE src/WatchdogModule.cpp)
3+
target_include_directories(WatchdogModule PUBLIC include)
4+
target_link_libraries(WatchdogModule
5+
PRIVATE
6+
WatchdogWrapper
7+
mbed-os
8+
)

rover-apps/common/include/Module.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
#pragma once
2+
3+
class Module {
4+
public:
5+
virtual void periodic_10s(void) = 0;
6+
virtual void periodic_1s(void) = 0;
7+
virtual void periodic_100ms(void) = 0;
8+
virtual void periodic_10ms(void) = 0;
9+
virtual void periodic_1ms(void) = 0;
10+
};
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
#pragma once
2+
3+
#include "Module.h"
4+
#include "mbed.h"
5+
6+
class WatchdogModule final : public Module {
7+
public:
8+
/* Initiates the watchdog with a countdown
9+
* @param countdown - max timeout of the watchdog
10+
* */
11+
WatchdogModule();
12+
13+
// Periodic function to kick the watchdog and restart its timer every 1s
14+
void periodic_1s(void) override;
15+
16+
void periodic_10s(void) override {}
17+
void periodic_100ms(void) override {}
18+
void periodic_10ms(void) override {}
19+
void periodic_1ms(void) override {}
20+
21+
private:
22+
static const std::chrono::milliseconds WATCHDOG_DEFAULT_COUNTDOWN;
23+
};
Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
#include "WatchdogModule.h"
2+
3+
#include "Module.h"
4+
#include "WatchdogWrapper.h"
5+
#include "mbed.h"
6+
7+
const std::chrono::milliseconds WatchdogModule::WATCHDOG_DEFAULT_COUNTDOWN = 5000ms;
8+
9+
WatchdogModule::WatchdogModule() {
10+
Utility::WatchdogWrapper::logResetReason();
11+
Utility::WatchdogWrapper::startWatchdog(WATCHDOG_DEFAULT_COUNTDOWN);
12+
}
13+
14+
void WatchdogModule::periodic_1s(void) {
15+
Utility::WatchdogWrapper::petWatchdog();
16+
}

rover-apps/common/src/main.cpp

Lines changed: 85 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,85 @@
1+
#include "AppConfig.h"
2+
#include "Logger.h"
3+
#include "mbed.h"
4+
5+
Thread periodic_10s_thread(osPriorityHigh);
6+
Thread periodic_1s_thread(osPriorityHigh2);
7+
Thread periodic_100ms_thread(osPriorityHigh4);
8+
Thread periodic_10ms_thread(osPriorityHigh6);
9+
Thread periodic_1ms_thread(osPriorityRealtime);
10+
11+
void periodic_10s(void) {
12+
auto startTime = Kernel::Clock::now();
13+
for (Module* module : gModules) {
14+
module->periodic_10s();
15+
}
16+
17+
auto nextStartTime = startTime + 10s;
18+
if (Kernel::Clock::now() > nextStartTime) {
19+
Utility::logger << "Periodic 10s task failed to hit the deadline!\n";
20+
}
21+
ThisThread::sleep_until(nextStartTime);
22+
}
23+
24+
void periodic_1s(void) {
25+
auto startTime = Kernel::Clock::now();
26+
for (Module* module : gModules) {
27+
module->periodic_1s();
28+
}
29+
30+
auto nextStartTime = startTime + 1s;
31+
if (Kernel::Clock::now() > nextStartTime) {
32+
Utility::logger << "Periodic 1s task failed to hit the deadline!\n";
33+
}
34+
ThisThread::sleep_until(nextStartTime);
35+
}
36+
37+
void periodic_100ms(void) {
38+
auto startTime = Kernel::Clock::now();
39+
for (Module* module : gModules) {
40+
module->periodic_100ms();
41+
}
42+
43+
auto nextStartTime = startTime + 100ms;
44+
if (Kernel::Clock::now() > nextStartTime) {
45+
Utility::logger << "Periodic 100ms task failed to hit the deadline!\n";
46+
}
47+
ThisThread::sleep_until(nextStartTime);
48+
}
49+
50+
void periodic_10ms(void) {
51+
auto startTime = Kernel::Clock::now();
52+
for (Module* module : gModules) {
53+
module->periodic_10ms();
54+
}
55+
56+
auto nextStartTime = startTime + 10ms;
57+
if (Kernel::Clock::now() > nextStartTime) {
58+
Utility::logger << "Periodic 10ms task failed to hit the deadline!\n";
59+
}
60+
ThisThread::sleep_until(nextStartTime);
61+
}
62+
63+
void periodic_1ms(void) {
64+
auto startTime = Kernel::Clock::now();
65+
for (Module* module : gModules) {
66+
module->periodic_1ms();
67+
}
68+
69+
auto nextStartTime = startTime + 1ms;
70+
if (Kernel::Clock::now() > nextStartTime) {
71+
Utility::logger << "Periodic 1ms task failed to hit the deadline!\n";
72+
}
73+
ThisThread::sleep_until(nextStartTime);
74+
}
75+
76+
int main() {
77+
periodic_1ms_thread.start(periodic_1ms);
78+
periodic_10ms_thread.start(periodic_10ms);
79+
periodic_100ms_thread.start(periodic_100ms);
80+
periodic_1s_thread.start(periodic_1s);
81+
periodic_10s_thread.start(periodic_10s);
82+
83+
while (true) {
84+
}
85+
}

0 commit comments

Comments
 (0)