mirror of
https://github.com/yoboujon/dumber.git
synced 2025-06-08 13:50:49 +02:00
Premiere version entirement debuggée et fonctionelle
This commit is contained in:
parent
1d27411326
commit
beefcb3ca8
10 changed files with 223 additions and 50 deletions
|
@ -329,7 +329,7 @@
|
||||||
</fileInfo>
|
</fileInfo>
|
||||||
<fileInfo id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.1504381080.727722516.1184097105" name="application.c" rcbsApplicability="disable" resourcePath="Application/application.c" toolsToInvoke="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985.298003348">
|
<fileInfo id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.1504381080.727722516.1184097105" name="application.c" rcbsApplicability="disable" resourcePath="Application/application.c" toolsToInvoke="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985.298003348">
|
||||||
<tool id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985.298003348" name="MCU GCC Compiler" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985">
|
<tool id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985.298003348" name="MCU GCC Compiler" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.1017015985">
|
||||||
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level.235309210" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level.value.o0" valueType="enumerated"/>
|
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level.235309210" name="Optimization level" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.optimization.level.value.o0" valueType="enumerated"/>
|
||||||
<inputType id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c.1492946438" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c"/>
|
<inputType id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c.1492946438" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c"/>
|
||||||
</tool>
|
</tool>
|
||||||
<tool customBuildStep="true" id="org.eclipse.cdt.managedbuilder.ui.rcbs.693102693" name="Resource Custom Build Step">
|
<tool customBuildStep="true" id="org.eclipse.cdt.managedbuilder.ui.rcbs.693102693" name="Resource Custom Build Step">
|
||||||
|
|
|
@ -171,6 +171,7 @@ void APPLICATION_MainThread(void* params) {
|
||||||
}
|
}
|
||||||
|
|
||||||
free(decodedCmd);
|
free(decodedCmd);
|
||||||
|
free(receivedCMD);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
@ -200,6 +201,7 @@ void APPLICATION_MainThread(void* params) {
|
||||||
case MSG_ID_BAT_MED:
|
case MSG_ID_BAT_MED:
|
||||||
case MSG_ID_BAT_HIGH:
|
case MSG_ID_BAT_HIGH:
|
||||||
systemInfos.batteryUpdate=1;
|
systemInfos.batteryUpdate=1;
|
||||||
|
systemInfos.inCharge=0;
|
||||||
systemInfos.batteryState = msg.id;
|
systemInfos.batteryState = msg.id;
|
||||||
break;
|
break;
|
||||||
case MSG_ID_MOTEURS_END_OF_MOUVMENT:
|
case MSG_ID_MOTEURS_END_OF_MOUVMENT:
|
||||||
|
@ -226,11 +228,11 @@ void APPLICATION_StateMachine() {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (systemInfos.batteryUpdate) {
|
if (systemInfos.batteryUpdate) {
|
||||||
ledState = leds_off;
|
|
||||||
|
|
||||||
if (systemInfos.batteryState==MSG_ID_BAT_CRITICAL_LOW) {
|
if (systemInfos.batteryState==MSG_ID_BAT_CRITICAL_LOW) {
|
||||||
ledState = leds_bat_critical_low;
|
ledState = leds_bat_critical_low;
|
||||||
APPLICATION_TransitionToNewState(stateLowBatDisable);
|
APPLICATION_TransitionToNewState(stateLowBatDisable);
|
||||||
|
|
||||||
|
LEDS_Set(ledState);
|
||||||
} else if (systemInfos.state == stateInCharge) {
|
} else if (systemInfos.state == stateInCharge) {
|
||||||
switch (systemInfos.batteryState) {
|
switch (systemInfos.batteryState) {
|
||||||
case MSG_ID_BAT_CHARGE_COMPLETE:
|
case MSG_ID_BAT_CHARGE_COMPLETE:
|
||||||
|
@ -246,6 +248,8 @@ void APPLICATION_StateMachine() {
|
||||||
ledState= leds_bat_charge_low;
|
ledState= leds_bat_charge_low;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
LEDS_Set(ledState);
|
||||||
} else if (systemInfos.state==stateStartup) {
|
} else if (systemInfos.state==stateStartup) {
|
||||||
switch (systemInfos.batteryState) {
|
switch (systemInfos.batteryState) {
|
||||||
case MSG_ID_BAT_HIGH:
|
case MSG_ID_BAT_HIGH:
|
||||||
|
@ -258,10 +262,10 @@ void APPLICATION_StateMachine() {
|
||||||
ledState= leds_bat_low;
|
ledState= leds_bat_low;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
LEDS_Set(ledState);
|
LEDS_Set(ledState);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (systemInfos.cmd != CMD_NONE) {
|
if (systemInfos.cmd != CMD_NONE) {
|
||||||
/* a newer command just arrived, process it
|
/* a newer command just arrived, process it
|
||||||
|
@ -271,7 +275,8 @@ void APPLICATION_StateMachine() {
|
||||||
case CMD_RESET:
|
case CMD_RESET:
|
||||||
if ((systemInfos.state == stateIdle) ||
|
if ((systemInfos.state == stateIdle) ||
|
||||||
(systemInfos.state == stateRun) ||
|
(systemInfos.state == stateRun) ||
|
||||||
(systemInfos.state == stateInMouvement)) {
|
(systemInfos.state == stateInMouvement) ||
|
||||||
|
(systemInfos.state == stateWatchdogDisable)) {
|
||||||
/* command RESET is only applicable in those 3 states, otherwise it is rejected */
|
/* command RESET is only applicable in those 3 states, otherwise it is rejected */
|
||||||
cmdSendAnswer(ANS_OK);
|
cmdSendAnswer(ANS_OK);
|
||||||
APPLICATION_TransitionToNewState(stateIdle);
|
APPLICATION_TransitionToNewState(stateIdle);
|
||||||
|
@ -284,31 +289,34 @@ void APPLICATION_StateMachine() {
|
||||||
/* only state where START cmd is accepted */
|
/* only state where START cmd is accepted */
|
||||||
cmdSendAnswer(ANS_OK);
|
cmdSendAnswer(ANS_OK);
|
||||||
|
|
||||||
APPLICATION_TransitionToNewState(stateRun);
|
|
||||||
|
|
||||||
if (systemInfos.cmd == CMD_START_WITH_WATCHDOG) {
|
if (systemInfos.cmd == CMD_START_WITH_WATCHDOG) {
|
||||||
systemTimeout.watchdogEnabled = 1;
|
systemTimeout.watchdogEnabled = 1;
|
||||||
systemTimeout.watchdogCnt=0;
|
systemTimeout.watchdogCnt=0;
|
||||||
systemTimeout.watchdogMissedCnt=0;
|
systemTimeout.watchdogMissedCnt=0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
APPLICATION_TransitionToNewState(stateRun);
|
||||||
} else
|
} else
|
||||||
cmdSendAnswer(ANS_ERR);
|
cmdSendAnswer(ANS_ERR);
|
||||||
break;
|
break;
|
||||||
case CMD_RESET_WATCHDOG:
|
case CMD_RESET_WATCHDOG:
|
||||||
if ((systemInfos.state == stateRun) || (systemInfos.state == stateInMouvement)) {
|
if ((systemInfos.state == stateRun) || (systemInfos.state == stateInMouvement)) {
|
||||||
if ((systemTimeout.watchdogEnabled ==0 ) ||
|
if ((systemTimeout.watchdogEnabled ==0 ) ||
|
||||||
((systemTimeout.watchdogCnt>=APPLICATION_WATCHDOG_MIN) && (systemTimeout.watchdogCnt<=APPLICATION_WATCHDOG_MAX)))
|
((systemTimeout.watchdogCnt>=(APPLICATION_WATCHDOG_MIN/100)) && (systemTimeout.watchdogCnt<=(APPLICATION_WATCHDOG_MAX/100)))) {
|
||||||
|
systemTimeout.watchdogMissedCnt=0; // gg, watchog is reset correctly
|
||||||
cmdSendAnswer(ANS_OK);
|
cmdSendAnswer(ANS_OK);
|
||||||
else
|
} else {
|
||||||
|
systemTimeout.watchdogMissedCnt++; // If you reset at the wrong time, it still count as missed watchdog reset
|
||||||
cmdSendAnswer(ANS_ERR);
|
cmdSendAnswer(ANS_ERR);
|
||||||
|
}
|
||||||
|
|
||||||
systemTimeout.watchdogCnt =0;
|
systemTimeout.watchdogCnt =0;
|
||||||
}
|
} else
|
||||||
|
cmdSendAnswer(ANS_ERR);
|
||||||
break;
|
break;
|
||||||
case CMD_MOVE:
|
case CMD_MOVE:
|
||||||
case CMD_TURN:
|
case CMD_TURN:
|
||||||
if (systemInfos.state == stateRun) { // only state where MOVE or TURN cmds are accepted
|
if (systemInfos.state == stateRun) { // only state where MOVE or TURN cmds are accepted
|
||||||
|
|
||||||
if (((systemInfos.cmd == CMD_MOVE) && (systemInfos.distance !=0)) ||
|
if (((systemInfos.cmd == CMD_MOVE) && (systemInfos.distance !=0)) ||
|
||||||
((systemInfos.cmd == CMD_TURN) && (systemInfos.turns !=0))) {
|
((systemInfos.cmd == CMD_TURN) && (systemInfos.turns !=0))) {
|
||||||
systemInfos.endOfMouvement = 0;
|
systemInfos.endOfMouvement = 0;
|
||||||
|
@ -320,6 +328,8 @@ void APPLICATION_StateMachine() {
|
||||||
((systemInfos.cmd == CMD_TURN) && (systemInfos.turns ==0))) {
|
((systemInfos.cmd == CMD_TURN) && (systemInfos.turns ==0))) {
|
||||||
systemInfos.endOfMouvement = 1;
|
systemInfos.endOfMouvement = 1;
|
||||||
cmdSendAnswer(ANS_OK);
|
cmdSendAnswer(ANS_OK);
|
||||||
|
} else { // If MOVE and TURN cmds come with parameters, reject them
|
||||||
|
cmdSendAnswer(ANS_ERR);
|
||||||
}
|
}
|
||||||
} else
|
} else
|
||||||
cmdSendAnswer(ANS_ERR);
|
cmdSendAnswer(ANS_ERR);
|
||||||
|
@ -329,7 +339,7 @@ void APPLICATION_StateMachine() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (systemInfos.endOfMouvement) {
|
if ((systemInfos.state==stateInMouvement) && (systemInfos.endOfMouvement)) {
|
||||||
APPLICATION_TransitionToNewState(stateRun);
|
APPLICATION_TransitionToNewState(stateRun);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -342,14 +352,14 @@ void APPLICATION_StateMachine() {
|
||||||
}
|
}
|
||||||
|
|
||||||
systemInfos.batteryUpdate = 0;
|
systemInfos.batteryUpdate = 0;
|
||||||
systemInfos.cmd =0;
|
systemInfos.cmd = CMD_NONE;
|
||||||
systemInfos.endOfMouvement =0;
|
systemInfos.endOfMouvement =0;
|
||||||
systemInfos.powerOffRequired=0;
|
systemInfos.powerOffRequired=0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void APPLICATION_TransitionToNewState(APPLICATION_State new_state) {
|
void APPLICATION_TransitionToNewState(APPLICATION_State new_state) {
|
||||||
LEDS_State ledState = leds_off;
|
LEDS_State ledState = leds_off;
|
||||||
int32_t data;
|
//int32_t data;
|
||||||
|
|
||||||
switch (new_state) {
|
switch (new_state) {
|
||||||
case stateStartup:
|
case stateStartup:
|
||||||
|
@ -359,30 +369,32 @@ void APPLICATION_TransitionToNewState(APPLICATION_State new_state) {
|
||||||
ledState = leds_idle;
|
ledState = leds_idle;
|
||||||
LEDS_Set(ledState);
|
LEDS_Set(ledState);
|
||||||
|
|
||||||
MESSAGE_SendMailbox(MOTEURS_Mailbox, MSG_ID_MOTEURS_STOP, APPLICATION_Mailbox, (void*)NULL);
|
MOTEURS_Stop();
|
||||||
systemTimeout.watchdogEnabled=0;
|
systemTimeout.watchdogEnabled=0;
|
||||||
break;
|
break;
|
||||||
case stateRun:
|
case stateRun:
|
||||||
|
if (systemTimeout.watchdogEnabled)
|
||||||
|
ledState = leds_run_with_watchdog;
|
||||||
|
else
|
||||||
ledState = leds_run;
|
ledState = leds_run;
|
||||||
|
|
||||||
LEDS_Set(ledState);
|
LEDS_Set(ledState);
|
||||||
|
|
||||||
MESSAGE_SendMailbox(MOTEURS_Mailbox, MSG_ID_MOTEURS_STOP, APPLICATION_Mailbox, (void*)NULL);
|
MOTEURS_Stop();
|
||||||
break;
|
break;
|
||||||
case stateInMouvement:
|
case stateInMouvement:
|
||||||
ledState = leds_run;
|
ledState = leds_run;
|
||||||
LEDS_Set(ledState);
|
LEDS_Set(ledState);
|
||||||
|
|
||||||
if (systemInfos.cmd == CMD_MOVE) {
|
if (systemInfos.cmd == CMD_MOVE) {
|
||||||
data = systemInfos.distance;
|
MOTEURS_Avance( systemInfos.distance);
|
||||||
MESSAGE_SendMailbox(MOTEURS_Mailbox, MSG_ID_MOTEURS_MOVE, APPLICATION_Mailbox, (void*)&data);
|
|
||||||
} else { /* obviously, cmd is CMD_TURN */
|
} else { /* obviously, cmd is CMD_TURN */
|
||||||
data = systemInfos.turns;
|
MOTEURS_Tourne(systemInfos.turns);
|
||||||
MESSAGE_SendMailbox(MOTEURS_Mailbox, MSG_ID_MOTEURS_TURN, APPLICATION_Mailbox, (void*)&data);
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case stateInCharge:
|
case stateInCharge:
|
||||||
/* les leds sont gerées dans APPLICATION_StateMachine */
|
/* les leds sont gerées dans APPLICATION_StateMachine */
|
||||||
MESSAGE_SendMailbox(MOTEURS_Mailbox, MSG_ID_MOTEURS_STOP, APPLICATION_Mailbox, (void*)NULL);
|
MOTEURS_Stop();
|
||||||
systemTimeout.watchdogEnabled=0;
|
systemTimeout.watchdogEnabled=0;
|
||||||
break;
|
break;
|
||||||
case stateWatchdogDisable:
|
case stateWatchdogDisable:
|
||||||
|
@ -413,7 +425,7 @@ void APPLICATION_PowerOff() {
|
||||||
/*
|
/*
|
||||||
* TODO: a decommenter quand le code sera debuggé
|
* TODO: a decommenter quand le code sera debuggé
|
||||||
*/
|
*/
|
||||||
//HAL_GPIO_WritePin(SHUTDOWN_GPIO_Port, SHUTDOWN_Pin, GPIO_PIN_RESET);
|
HAL_GPIO_WritePin(SHUTDOWN_GPIO_Port, SHUTDOWN_Pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
while (1){
|
while (1){
|
||||||
__WFE(); // Attente infinie que le regulateur se coupe.
|
__WFE(); // Attente infinie que le regulateur se coupe.
|
||||||
|
@ -442,9 +454,9 @@ void vTimerTimeoutCallback( TimerHandle_t xTimer ) {
|
||||||
if (systemTimeout.watchdogCnt>(APPLICATION_WATCHDOG_MAX/100)) {
|
if (systemTimeout.watchdogCnt>(APPLICATION_WATCHDOG_MAX/100)) {
|
||||||
systemTimeout.watchdogCnt=0;
|
systemTimeout.watchdogCnt=0;
|
||||||
systemTimeout.watchdogMissedCnt++;
|
systemTimeout.watchdogMissedCnt++;
|
||||||
|
}
|
||||||
|
|
||||||
if (systemTimeout.watchdogMissedCnt>=(APPLICATION_WATCHDOG_MISSED_MAX/100))
|
if (systemTimeout.watchdogMissedCnt>=APPLICATION_WATCHDOG_MISSED_MAX)
|
||||||
APPLICATION_TransitionToNewState(stateWatchdogDisable); /* TODO: Reprendre pour en faire un envoi de message */
|
APPLICATION_TransitionToNewState(stateWatchdogDisable); /* TODO: Reprendre pour en faire un envoi de message */
|
||||||
}
|
}
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -17,6 +17,8 @@ typedef enum {
|
||||||
CHARGEUR_ERROR
|
CHARGEUR_ERROR
|
||||||
} BATTERIE_StatusChargerTypedef;
|
} BATTERIE_StatusChargerTypedef;
|
||||||
|
|
||||||
|
#define BATTERIE_MAX_ERROR 3
|
||||||
|
|
||||||
extern ADC_HandleTypeDef hadc;
|
extern ADC_HandleTypeDef hadc;
|
||||||
uint8_t conversion_complete;
|
uint8_t conversion_complete;
|
||||||
uint16_t adc_raw_value;
|
uint16_t adc_raw_value;
|
||||||
|
@ -125,16 +127,31 @@ int BATTERIE_LireTension(uint16_t *val) {
|
||||||
* Tension batterie: 2.9 critic 3.1 low 3.3 med 3.6 high 4.2
|
* Tension batterie: 2.9 critic 3.1 low 3.3 med 3.6 high 4.2
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#define BATTERIE_LEVEL_CRITICAL 200
|
#ifdef TESTS
|
||||||
#define BATTERIE_LEVEL_LOW 300
|
uint8_t BATTERIE_LEVEL_CRITICAL=135;
|
||||||
#define BATTERIE_LEVEL_HIGH 500
|
uint8_t BATTERIE_LEVEL_LOW=145;
|
||||||
|
uint8_t BATTERIE_LEVEL_HIGH=155;
|
||||||
|
|
||||||
#define BATTERIE_LEVEL_CHARGE_LOW 400
|
uint8_t BATTERIE_LEVEL_CHARGE_LOW=150;
|
||||||
#define BATTERIE_LEVEL_CHARGE_HIGH 700
|
uint8_t BATTERIE_LEVEL_CHARGE_HIGH=170;
|
||||||
|
|
||||||
|
uint8_t BATTERIE_currentValue;
|
||||||
|
#else
|
||||||
|
#define BATTERIE_LEVEL_CRITICAL 135
|
||||||
|
#define BATTERIE_LEVEL_LOW 145
|
||||||
|
#define BATTERIE_LEVEL_HIGH 155
|
||||||
|
|
||||||
|
#define BATTERIE_LEVEL_CHARGE_LOW 150
|
||||||
|
#define BATTERIE_LEVEL_CHARGE_HIGH 170
|
||||||
|
#endif /* TESTS */
|
||||||
|
|
||||||
uint16_t BATTERIE_BatteryLevel(uint8_t voltage, BATTERIE_StatusChargerTypedef chargerStatus) {
|
uint16_t BATTERIE_BatteryLevel(uint8_t voltage, BATTERIE_StatusChargerTypedef chargerStatus) {
|
||||||
uint16_t msgId=0;
|
uint16_t msgId=0;
|
||||||
|
|
||||||
|
#ifdef TESTS
|
||||||
|
BATTERIE_currentValue=voltage;
|
||||||
|
#endif /* TESTS */
|
||||||
|
|
||||||
switch (chargerStatus) {
|
switch (chargerStatus) {
|
||||||
case CHARGEUR_CHARGE_COMPLETE:
|
case CHARGEUR_CHARGE_COMPLETE:
|
||||||
msgId = MSG_ID_BAT_CHARGE_COMPLETE;
|
msgId = MSG_ID_BAT_CHARGE_COMPLETE;
|
||||||
|
@ -166,6 +183,7 @@ uint16_t BATTERIE_BatteryLevel(uint8_t voltage, BATTERIE_StatusChargerTypedef ch
|
||||||
|
|
||||||
void BATTERIE_VoltageThread(void* params) {
|
void BATTERIE_VoltageThread(void* params) {
|
||||||
static uint16_t tension;
|
static uint16_t tension;
|
||||||
|
static uint8_t batteryErrorCnt=0;
|
||||||
BATTERIE_StatusChargerTypedef currentStatus;
|
BATTERIE_StatusChargerTypedef currentStatus;
|
||||||
uint16_t messageID;
|
uint16_t messageID;
|
||||||
|
|
||||||
|
@ -177,17 +195,15 @@ void BATTERIE_VoltageThread(void* params) {
|
||||||
while (1) {
|
while (1) {
|
||||||
if (BATTERIE_LireTension(&tension) ==0) {
|
if (BATTERIE_LireTension(&tension) ==0) {
|
||||||
currentStatus = BATTERIE_LireStatusChargeur();
|
currentStatus = BATTERIE_LireStatusChargeur();
|
||||||
if (currentStatus == CHARGEUR_ERROR)
|
if (currentStatus == CHARGEUR_ERROR) {
|
||||||
|
batteryErrorCnt++;
|
||||||
|
|
||||||
|
if (batteryErrorCnt>=BATTERIE_MAX_ERROR)
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_CHARGE_ERR, (QueueHandle_t)0x0, (void*)NULL);
|
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_CHARGE_ERR, (QueueHandle_t)0x0, (void*)NULL);
|
||||||
/*else if (currentStatus == CHARGEUR_IN_CHARGE)
|
} else {
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_CHARGE_ON, (QueueHandle_t)0x0, (void*)&tension);
|
|
||||||
else if (currentStatus == CHARGEUR_CHARGE_COMPLETE)
|
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_CHARGE_COMPLETE, (QueueHandle_t)0x0, (void*)&tension);
|
|
||||||
else
|
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_CHARGE_OFF, (QueueHandle_t)0x0, (void*)&tension);*/
|
|
||||||
messageID = BATTERIE_BatteryLevel(tension, currentStatus);
|
messageID = BATTERIE_BatteryLevel(tension, currentStatus);
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, messageID, (QueueHandle_t)0x0, (void*)NULL);
|
MESSAGE_SendMailbox(APPLICATION_Mailbox, messageID, (QueueHandle_t)0x0, (void*)NULL);
|
||||||
|
}
|
||||||
#ifdef TESTS
|
#ifdef TESTS
|
||||||
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_LEVEL, (QueueHandle_t)0x0, (void*)&tension);
|
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_BAT_LEVEL, (QueueHandle_t)0x0, (void*)&tension);
|
||||||
#endif /* TESTS*/
|
#endif /* TESTS*/
|
||||||
|
|
|
@ -355,9 +355,9 @@ void LEDS_ActionThread(void* params) {
|
||||||
cnt=0;
|
cnt=0;
|
||||||
break;
|
break;
|
||||||
case leds_watchdog_expired:
|
case leds_watchdog_expired:
|
||||||
if (cnt<3)
|
if (cnt<4)
|
||||||
LEDS_ShowPattern(LED_PATTERN_WDT_EXP_1);
|
LEDS_ShowPattern(LED_PATTERN_WDT_EXP_1);
|
||||||
else if (cnt<6)
|
else if (cnt<7)
|
||||||
LEDS_ShowPattern(LED_PATTERN_WDT_EXP_2);
|
LEDS_ShowPattern(LED_PATTERN_WDT_EXP_2);
|
||||||
else
|
else
|
||||||
cnt=0;
|
cnt=0;
|
||||||
|
|
|
@ -236,10 +236,13 @@ void MOTEURS_TachePrincipale(void *params) {
|
||||||
MOTEURS_EtatMoteurGauche.consigne = 0;
|
MOTEURS_EtatMoteurGauche.consigne = 0;
|
||||||
MOTEURS_EtatMoteurDroit.consigne = 0;
|
MOTEURS_EtatMoteurDroit.consigne = 0;
|
||||||
if ((MOTEURS_CorrectionEncodeur(MOTEURS_EtatMoteurGauche) == 0)
|
if ((MOTEURS_CorrectionEncodeur(MOTEURS_EtatMoteurGauche) == 0)
|
||||||
&& (MOTEURS_CorrectionEncodeur(MOTEURS_EtatMoteurDroit) == 0))
|
&& (MOTEURS_CorrectionEncodeur(MOTEURS_EtatMoteurDroit) == 0)) {
|
||||||
// Les moteurs sont déjà arrêtés
|
// Les moteurs sont déjà arrêtés
|
||||||
vTaskSuspend(xHandleMoteursAsservissement);
|
vTaskSuspend(xHandleMoteursAsservissement);
|
||||||
else
|
|
||||||
|
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_MOTEURS_END_OF_MOUVMENT,
|
||||||
|
MOTEURS_Mailbox, (void*) NULL);
|
||||||
|
} else
|
||||||
// Les moteurs tournent encore
|
// Les moteurs tournent encore
|
||||||
vTaskResume(xHandleMoteursAsservissement);
|
vTaskResume(xHandleMoteursAsservissement);
|
||||||
break;
|
break;
|
||||||
|
@ -289,6 +292,8 @@ void MOTEURS_TacheAsservissement(void *params) {
|
||||||
&& ((erreurD == 0) && (erreurG == 0))) {
|
&& ((erreurD == 0) && (erreurG == 0))) {
|
||||||
|
|
||||||
MOTEURS_DesactiveAlim();
|
MOTEURS_DesactiveAlim();
|
||||||
|
MESSAGE_SendMailbox(APPLICATION_Mailbox, MSG_ID_MOTEURS_END_OF_MOUVMENT,
|
||||||
|
MOTEURS_Mailbox, (void*) NULL);
|
||||||
vTaskSuspend(xHandleMoteursAsservissement);
|
vTaskSuspend(xHandleMoteursAsservissement);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -49,8 +49,8 @@ void PANIC_StopTasksAndWait(void){
|
||||||
currentTask = xTaskGetCurrentTaskHandle();
|
currentTask = xTaskGetCurrentTaskHandle();
|
||||||
|
|
||||||
/* Arret des timers */
|
/* Arret des timers */
|
||||||
xTimerStop(xHandleTimerButton,0);
|
//xTimerStop(xHandleTimerButton,0);
|
||||||
xTimerStop(xHandleTimerTimeout,0);
|
//xTimerStop(xHandleTimerTimeout,0);
|
||||||
|
|
||||||
/* Arret des taches
|
/* Arret des taches
|
||||||
* On n'arrete toute les taches sauf celle en cours !
|
* On n'arrete toute les taches sauf celle en cours !
|
||||||
|
|
45
software/dumber3/Commands tests WDT.xml
Normal file
45
software/dumber3/Commands tests WDT.xml
Normal file
|
@ -0,0 +1,45 @@
|
||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
|
||||||
|
<data>
|
||||||
|
<loop>true</loop>
|
||||||
|
<repeat_times>1</repeat_times>
|
||||||
|
<repeat_period>1100</repeat_period>
|
||||||
|
<packets_list>
|
||||||
|
<packet name="Reset">
|
||||||
|
<payload>72720D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Start With Watchdog">
|
||||||
|
<payload>57570D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
<packet name="Reset Watchdog - Copy - Copy - Copy - Copy - Copy - Copy - Copy - Copy - Copy">
|
||||||
|
<payload>77770D</payload>
|
||||||
|
</packet>
|
||||||
|
</packets_list>
|
||||||
|
</data>
|
|
@ -24,7 +24,10 @@
|
||||||
/* Private includes ----------------------------------------------------------*/
|
/* Private includes ----------------------------------------------------------*/
|
||||||
/* USER CODE BEGIN Includes */
|
/* USER CODE BEGIN Includes */
|
||||||
#include "application.h"
|
#include "application.h"
|
||||||
|
|
||||||
|
#ifdef TESTS
|
||||||
#include "tests.h"
|
#include "tests.h"
|
||||||
|
#endif /* TESTS */
|
||||||
|
|
||||||
/* USER CODE END Includes */
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
|
|
83
software/dumber3/Dumber3 Debug.launch
Normal file
83
software/dumber3/Dumber3 Debug.launch
Normal file
|
@ -0,0 +1,83 @@
|
||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<launchConfiguration type="com.st.stm32cube.ide.mcu.debug.launch.launchConfigurationType">
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.access_port_id" value="0"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.cubeprog_external_loaders" value="[]"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_certif_path" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_check_enable" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_key_path" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_permission" value="debug_non_secure_L3"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_live_expr" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_swv" value="false"/>
|
||||||
|
<intAttribute key="com.st.stm32cube.ide.mcu.debug.launch.formatVersion" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.ip_address_local" value="localhost"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.limit_swo_clock.enabled" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.limit_swo_clock.value" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.loadList" value="{"fItems":[{"fIsFromMainTab":true,"fPath":"Debug/Dumber3.elf","fProjectName":"Dumber3","fPerformBuild":true,"fDownload":true,"fLoadSymbols":true}]}"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.override_start_address_mode" value="default"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.remoteCommand" value="target remote"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startServer" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.divby0" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.unaligned" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.haltonexception" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swd_mode" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_port" value="61235"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_hclk" value="16000000"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.useRemoteTarget" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.vector_table" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.verify_flash_download" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_allow_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_signal_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_logging" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_max_halt_delay" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_shared_stlink" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.frequency" value="0"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.halt_all_on_reset" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.log_file" value="/home/dimercur/Travail/git/dumber/software/dumber3/Debug/st-link_gdbserver_log.txt"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.low_power_debug" value="enable"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.max_halt_delay" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.reset_strategy" value="connect_under_reset"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_check_serial_number" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_txt_serial_number" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.watchdog_config" value="enable"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkenable_rtos" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkrestart_configurations" value="{"fVersion":1,"fItems":[{"fDisplayName":"Reset","fIsSuppressible":false,"fResetAttribute":"Software system reset","fResetStrategies":[{"fDisplayName":"Software system reset","fLaunchAttribute":"system_reset","fGdbCommands":["monitor reset\n"],"fCmdOptions":["-g"]},{"fDisplayName":"Hardware reset","fLaunchAttribute":"hardware_reset","fGdbCommands":["monitor reset hardware\n"],"fCmdOptions":["-g"]},{"fDisplayName":"Core reset","fLaunchAttribute":"core_reset","fGdbCommands":["monitor reset core\n"],"fCmdOptions":["-g"]},{"fDisplayName":"None","fLaunchAttribute":"no_reset","fGdbCommands":[],"fCmdOptions":["-g"]}],"fGdbCommandGroup":{"name":"Additional commands","commands":[]},"fStartApplication":true}]}"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.enableRtosProxy" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyCustomProperties" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriver" value="freertos"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriverAuto" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriverPort" value="ARM_CM0"/>
|
||||||
|
<intAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyPort" value="60000"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doHalt" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doReset" value="false"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.initCommands" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.ipAddress" value="localhost"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.jtagDeviceId" value="com.st.stm32cube.ide.mcu.debug.stlink"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.pcRegister" value=""/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.debug.gdbjtag.core.portNumber" value="61234"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.runCommands" value=""/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setPcRegister" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setResume" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setStopAt" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.stopAt" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.dsf.gdb.DEBUG_NAME" value="arm-none-eabi-gdb"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.NON_STOP" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.UPDATE_THREADLIST_ON_SUSPEND" value="false"/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.launch.ATTR_BUILD_BEFORE_LAUNCH_ATTR" value="2"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.COREFILE_PATH" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_START_MODE" value="remote"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN_SYMBOL" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="Debug/Dumber3.elf"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="Dumber3"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.1504381080"/>
|
||||||
|
<booleanAttribute key="org.eclipse.debug.core.ATTR_FORCE_SYSTEM_CONSOLE_ENCODING" value="false"/>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
||||||
|
<listEntry value="/Dumber3"/>
|
||||||
|
</listAttribute>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
|
||||||
|
<listEntry value="4"/>
|
||||||
|
</listAttribute>
|
||||||
|
<stringAttribute key="org.eclipse.dsf.launch.MEMORY_BLOCKS" value="<?xml version="1.0" encoding="UTF-8" standalone="no"?><memoryBlockExpressionList context="reserved-for-future-use"/>"/>
|
||||||
|
<stringAttribute key="process_factory_id" value="com.st.stm32cube.ide.mcu.debug.launch.HardwareDebugProcessFactory"/>
|
||||||
|
</launchConfiguration>
|
|
@ -32,10 +32,11 @@ typedef enum {
|
||||||
COMMANDS_Tests,
|
COMMANDS_Tests,
|
||||||
BATTERY_Tests,
|
BATTERY_Tests,
|
||||||
MOTEURS_Tests,
|
MOTEURS_Tests,
|
||||||
MISC_Tests
|
MISC_Tests,
|
||||||
|
PANIC_Tests
|
||||||
} TESTS_Type;
|
} TESTS_Type;
|
||||||
|
|
||||||
TESTS_Type TESTS_Nbr=LEDS_Tests; // Number indicating which test is being run
|
TESTS_Type TESTS_Nbr=BATTERY_Tests; // Number indicating which test is being run
|
||||||
|
|
||||||
void TESTS_BasicTests(void* params);
|
void TESTS_BasicTests(void* params);
|
||||||
|
|
||||||
|
@ -328,6 +329,14 @@ void TESTS_BasicTests(void* params) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case PANIC_Tests: // test du bouton on/off
|
||||||
|
|
||||||
|
/* test si le systeme detecte qu'il n'y a plus de memoire et part en panic */
|
||||||
|
while (1) {
|
||||||
|
volatile char* str;
|
||||||
|
str = (char*)malloc(100); /* allocate a buffer of 100 bytes */
|
||||||
|
}
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Reference in a new issue