Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Code maintenance #1279

Merged
merged 2 commits into from
Apr 20, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .ci/doxygen.groovy
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ def call(config) {
Documentation/doxygen.sh"""
warnings canComputeNew: false, canResolveRelativePaths: false,
defaultEncoding: '',
excludePattern: '''.*/hal/architecture/Linux/drivers/.*,.*/drivers/TinyGSM/.*''',
excludePattern: '''.*/hal/architecture/Linux/drivers/.*,.*/hal/architecture/AVR/drivers/.*,.*/drivers/TinyGSM/.*''',
failedTotalAll: '', healthy: '', includePattern: '', messagesPattern: '',
parserConfigurations: [[parserName: 'Doxygen', pattern: config.repository_root+'doxygen.log']],
unHealthy: '', unstableTotalAll: '0'
Expand Down
2 changes: 1 addition & 1 deletion .mystools/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

This directory hosts MySensors development tools. The following
conventions are employed to facilitate consistent re-use/invocation
across modalitiies (e.g. local development, continuous integration,
across modalities (e.g. local development, continuous integration,
editor linters, etc.)

1. All common tools are hosted and managed in
Expand Down
1 change: 0 additions & 1 deletion MyConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
*/
#ifndef MyConfig_h
#define MyConfig_h
#include <stdint.h>

/**
* @defgroup SerialDebugGrpPub Serial and debugging
Expand Down
1 change: 1 addition & 0 deletions MySensors.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#ifdef __cplusplus
#include <Arduino.h>
#endif
#include <stdint.h>

#include "MyConfig.h"
#include "core/MyHelperFunctions.cpp"
Expand Down
13 changes: 7 additions & 6 deletions configure
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# Original work: https://github.com/TMRh20/RF24/blob/master/configure

function help {
cat <<EOF
cat <<EOF
configure script for MySensors gateway.
Options:

Expand Down Expand Up @@ -62,10 +62,10 @@ MySensors options:
MQTT publish topic prefix.
--my-mqtt-subscribe-topic-prefix=<PREFIX>
MQTT subscribe topic prefix.
--my-transport=[none|rf24|rs485|rfm95|rfm69]
--my-transport=[none|rf24|rfm69|rfm95|rs485]
Set the transport to be used to communicate with other nodes. [rf24]
--my-rf24-channel=<0-125> RF channel for the sensor net. [76]
--my-rf24-pa-level=[RF24_PA_MAX|RF24_PA_LOW]
--my-rf24-pa-level=[RF24_PA_MAX|RF24_PA_HIGH|RF24_PA_LOW|RF24_PA_MIN]
RF24 PA level. [RF24_PA_MAX]
--my-rf24-ce-pin=<PIN> Pin number to use for rf24 Chip-Enable.
--my-rf24-cs-pin=<PIN> Pin number to use for rf24 Chip-Select.
Expand Down Expand Up @@ -318,7 +318,7 @@ for opt do
CFLAGS="$optarg"
;;
--extra-cxxflags=*)
CXXFLAGS="$optarg"
CXXFLAGS="$optarg $CXXFLAGS"
;;
--extra-ldflags=*)
LDFLAGS="$optarg"
Expand Down Expand Up @@ -542,6 +542,7 @@ BINDIR=${BINDIR:-bin}
GATEWAY_DIR=${GATEWAY_DIR:-${PREFIX}/bin}
CC=${CC:-gcc}
CXX=${CXX:-g++}
CXXFLAGS="-std=c++11"

if [ -z "${SOC}" ]; then
printf "${SECTION} Detecting target machine.\n"
Expand Down Expand Up @@ -625,10 +626,10 @@ elif [[ ${transport_type} == "rf24" ]]; then
CPPFLAGS="-DMY_RADIO_RF24 $CPPFLAGS"
elif [[ ${transport_type} == "rfm69" ]]; then
CPPFLAGS="-DMY_RADIO_RFM69 -DMY_RFM69_NEW_DRIVER $CPPFLAGS"
elif [[ ${transport_type} == "rs485" ]]; then
CPPFLAGS="-DMY_RS485 $CPPFLAGS"
elif [[ ${transport_type} == "rfm95" ]]; then
CPPFLAGS="-DMY_RADIO_RFM95 $CPPFLAGS"
elif [[ ${transport_type} == "rs485" ]]; then
CPPFLAGS="-DMY_RS485 $CPPFLAGS"
else
die "Invalid transport type." 3
fi
Expand Down
55 changes: 35 additions & 20 deletions core/MySensorsCore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,20 +19,14 @@

#include "MySensorsCore.h"

#if defined(__linux__)
#include <stdlib.h>
#include <unistd.h>
#endif

// debug output
#if defined(MY_DEBUG_VERBOSE_CORE)
#define CORE_DEBUG(x,...) DEBUG_OUTPUT(x, ##__VA_ARGS__) //!< debug
#else
#define CORE_DEBUG(x,...) //!< debug NULL
#define CORE_DEBUG(x,...) //!< debug NULL
#endif

// message buffers

MyMessage _msg; // Buffer for incoming messages
MyMessage _msgTmp; // Buffer for temporary messages (acks and nonces among others)

Expand All @@ -44,7 +38,7 @@ static uint8_t waitLock = 0;
#endif

#if defined(DEBUG_OUTPUT_ENABLED)
char _convBuf[MAX_PAYLOAD*2+1];
char _convBuf[MAX_PAYLOAD * 2 + 1];
#endif

// Callback for transport=ok transition
Expand Down Expand Up @@ -83,12 +77,13 @@ void _process(void)

void _infiniteLoop(void)
{
#if defined(__linux__)
exit(1);
#else
while(1) {
doYield();
#if defined(__linux__)
exit(1);
#endif
}
#endif
}

void _begin(void)
Expand Down Expand Up @@ -117,7 +112,7 @@ void _begin(void)
#if defined(F_CPU)
CORE_DEBUG(PSTR("MCO:BGN:INIT " MY_NODE_TYPE ",CP=" MY_CAPABILITIES ",FQ=%" PRIu16 ",REL=%"
PRIu8 ",VER="
MYSENSORS_LIBRARY_VERSION "\n"), (uint16_t)(F_CPU/1000000),
MYSENSORS_LIBRARY_VERSION "\n"), (uint16_t)(F_CPU/1000000UL),
MYSENSORS_LIBRARY_VERSION_PRERELEASE_NUMBER);
#else
CORE_DEBUG(PSTR("MCO:BGN:INIT " MY_NODE_TYPE ",CP=" MY_CAPABILITIES ",FQ=NA,REL=%"
Expand Down Expand Up @@ -147,7 +142,7 @@ void _begin(void)

// Read latest received controller configuration from EEPROM
// Note: _coreConfig.isMetric is bool, hence empty EEPROM (=0xFF) evaluates to true (default)
hwReadConfigBlock((void*)&_coreConfig.controllerConfig, (void*)EEPROM_CONTROLLER_CONFIG_ADDRESS,
hwReadConfigBlock((void *)&_coreConfig.controllerConfig, (void *)EEPROM_CONTROLLER_CONFIG_ADDRESS,
sizeof(controllerConfig_t));

#if defined(MY_OTA_FIRMWARE_FEATURE)
Expand Down Expand Up @@ -309,15 +304,15 @@ bool _sendRoute(MyMessage &message)
{
#if defined(MY_CORE_ONLY)
(void)message;
#endif
#if defined(MY_GATEWAY_FEATURE)
return false;
#elif defined(MY_GATEWAY_FEATURE)
if (message.destination == getNodeId()) {
// This is a message sent from a sensor attached on the gateway node.
// Pass it directly to the gateway transport layer.
return gatewayTransportSend(message);
}
#endif
#if defined(MY_SENSOR_NETWORK)
return false;
#elif defined(MY_SENSOR_NETWORK)
return transportSendRoute(message);
#else
return false;
Expand Down Expand Up @@ -560,6 +555,28 @@ void wait(const uint32_t waitingMS)
#endif
}

bool wait(const uint32_t waitingMS, const uint8_t cmd)
{
#if defined(MY_DEBUG_VERBOSE_CORE)
if (waitLock) {
CORE_DEBUG(PSTR("!MCO:WAI:RC=%" PRIu8 "\n"), waitLock); // recursive call detected
}
waitLock++;
#endif
const uint32_t enteringMS = hwMillis();
// invalidate cmd
mSetCommand(_msg, !cmd);
bool expectedResponse = false;
while ((hwMillis() - enteringMS < waitingMS) && !expectedResponse) {
_process();
expectedResponse = (mGetCommand(_msg) == cmd);
}
#if defined(MY_DEBUG_VERBOSE_CORE)
waitLock--;
#endif
return expectedResponse;
}

bool wait(const uint32_t waitingMS, const uint8_t cmd, const uint8_t msgType)
{
#if defined(MY_DEBUG_VERBOSE_CORE)
Expand All @@ -585,9 +602,7 @@ bool wait(const uint32_t waitingMS, const uint8_t cmd, const uint8_t msgType)
void doYield(void)
{
hwWatchdogReset();

yield();

#if defined (MY_DEFAULT_TX_LED_PIN) || defined(MY_DEFAULT_RX_LED_PIN) || defined(MY_DEFAULT_ERR_LED_PIN)
ledsProcess();
#endif
Expand Down Expand Up @@ -740,7 +755,7 @@ int8_t smartSleep(const uint8_t interrupt1, const uint8_t mode1, const uint8_t i



void _nodeLock(const char* str)
void _nodeLock(const char *str)
{
#ifdef MY_NODE_LOCK_FEATURE
// Make sure EEPROM is updated to locked status
Expand Down
22 changes: 16 additions & 6 deletions core/MySensorsCore.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,24 +51,23 @@
* |!| MCO | SND | NODE NOT REG | Node is not registered, cannot send message
* | | MCO | PIM | NODE REG=%%d | Registration response received, registration status (REG)
* |!| MCO | WAI | RC=%%d | Recursive call detected in wait(), level (RC)
* | | MCO | SLP | MS=%%lu,SMS=%%d,I1=%%d,M1=%%d,I2=%%d,M2=%%d | Sleep node, time (MS), smartSleep (SMS), Int1/M1, Int2/M2
* | | MCO | SLP | MS=%%lu,SMS=%%d,I1=%%d,M1=%%d,I2=%%d,M2=%%d | Sleep node, time (MS), smartSleep (SMS), Int1 (I1), Mode1 (M1), Int2 (I2), Mode2 (M2)
* | | MCO | SLP | WUP=%%d | Node woke-up, reason/IRQ (WUP)
* |!| MCO | SLP | NTL | Sleeping not possible, no time left
* |!| MCO | SLP | FWUPD | Sleeping not possible, FW update ongoing
* |!| MCO | SLP | REP | Sleeping not possible, repeater feature enabled
* |!| MCO | SLP | TNR | Transport not ready, attempt to reconnect until timeout (MY_SLEEP_TRANSPORT_RECONNECT_TIMEOUT_MS)
* |!| MCO | SLP | TNR | Transport not ready, attempt to reconnect until timeout (@ref MY_SLEEP_TRANSPORT_RECONNECT_TIMEOUT_MS)
* | | MCO | NLK | NODE LOCKED. UNLOCK: GND PIN %%d AND RESET | Node locked during booting, see signing chapter for additional information
* | | MCO | NLK | TSL | Set transport to sleep
*
*
* @brief API declaration for MySensorsCore
*/


#ifndef MySensorsCore_h
#define MySensorsCore_h

#include "Version.h" // Auto generated by bot
#include "Version.h"
#include "MyConfig.h"
#include "MyEepromAddresses.h"
#include "MyMessage.h"
Expand Down Expand Up @@ -136,7 +135,7 @@ void presentNode(void);
* @param description A textual description of the sensor.
* @return true Returns true if message reached the first stop on its way to destination.
*/
bool present(const uint8_t sensorId, const uint8_t sensorType, const char *description="",
bool present(const uint8_t sensorId, const uint8_t sensorType, const char *description = "",
const bool ack = false);
#if !defined(__linux__)
bool present(const uint8_t childSensorId, const uint8_t sensorType,
Expand Down Expand Up @@ -249,6 +248,17 @@ uint8_t loadState(const uint8_t pos);
*/
void wait(const uint32_t waitingMS);

/**
* Wait for a specified amount of time to pass or until specified message received. Keeps process()ing.
* This does not power-down the radio nor the Arduino.
* Because this calls process() in a loop, it is a good way to wait
* in your loop() on a repeater node or sensor that listens to messages.
* @param waitingMS Number of milliseconds to wait.
* @param cmd Command of incoming message.
* @return True if specified message received
*/
bool wait(const uint32_t waitingMS, const uint8_t cmd);

/**
* Wait for a specified amount of time to pass or until specified message received. Keeps process()ing.
* This does not power-down the radio nor the Arduino.
Expand Down Expand Up @@ -372,7 +382,7 @@ int8_t _sleep(const uint32_t sleepingMS, const bool smartSleep = false,
*
* @param str The string to transmit.
*/
void _nodeLock(const char* str);
void _nodeLock(const char *str);

/**
* @brief Check node lock status and prevent node execution if locked.
Expand Down
2 changes: 1 addition & 1 deletion core/MySigning.h
Original file line number Diff line number Diff line change
Expand Up @@ -765,7 +765,7 @@ int signerMemcmp(const void* a, const void* b, size_t sz);
* | | SGN | PRE | SGN NREQ,FROM='node' | Node 'node' does not require signing
* |!| SGN | PRE | SGN NREQ,FROM='node' REJ | Node 'node' does not require signing but used to (requirement remain unchanged)
* | | SGN | PRE | WHI REQ | Whitelisting required
* | | SGN | PRE | WHI REQ;TO='node' | Tell 'node' that we require whitelisting
* | | SGN | PRE | WHI REQ,TO='node' | Tell 'node' that we require whitelisting
* | | SGN | PRE | WHI REQ,FROM='node' | Node 'node' require whitelisting
* | | SGN | PRE | WHI NREQ | Whitelisting not required
* | | SGN | PRE | WHI NREQ,TO='node' | Tell 'node' that we do not require whitelisting
Expand Down
8 changes: 4 additions & 4 deletions core/MyTransport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -648,8 +648,8 @@ void transportProcessMessage(void)
(void)signerCheckTimer();
// receive message
setIndication(INDICATION_RX);
uint8_t payloadLength = transportReceive((uint8_t *)
&_msg.last); // last is the first byte of the payload buffer
// last is the first byte of the payload buffer
uint8_t payloadLength = transportReceive((uint8_t *)&_msg.last);
// get message length and limit size
const uint8_t msgLength = min(mGetLength(_msg), (uint8_t)MAX_PAYLOAD);
// calculate expected length
Expand Down Expand Up @@ -722,8 +722,8 @@ void transportProcessMessage(void)
if (mGetRequestAck(_msg)) {
TRANSPORT_DEBUG(PSTR("TSF:MSG:ACK REQ\n")); // ACK requested
_msgTmp = _msg; // Copy message
mSetRequestAck(_msgTmp,
false); // Reply without ack flag (otherwise we would end up in an eternal loop)
// Reply without ack flag (otherwise we would end up in an eternal loop)
mSetRequestAck(_msgTmp, false);
mSetAck(_msgTmp, true); // set ACK flag
_msgTmp.sender = _transportConfig.nodeId;
_msgTmp.destination = sender;
Expand Down
Loading