Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/3.5-dev' into v3.5-dev
Browse files Browse the repository at this point in the history
  • Loading branch information
gloomyandy committed Dec 1, 2024
2 parents 0b275bf + 0690b44 commit 0fa98e5
Show file tree
Hide file tree
Showing 49 changed files with 481 additions and 322 deletions.
2 changes: 1 addition & 1 deletion Tools/stackanalyzer/go.mod
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
module github.com/Duet3D/RepRapFirmware/Tools/stackanalyzer

go 1.15
go 1.21
Binary file modified Tools/stackanalyzer/linux/stackanalyzer
Binary file not shown.
Binary file modified Tools/stackanalyzer/macos/stackanalyzer
Binary file not shown.
25 changes: 15 additions & 10 deletions Tools/stackanalyzer/stackanalyzer.go
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@ package main

import (
"bufio"
"errors"
"flag"
"fmt"
"io"
Expand All @@ -13,13 +12,18 @@ import (
)

const (
assertionHeader = iota
assertionLineNo
lastSoftwareResetHeader = "Last software reset"
stackHeader = "Stack:"
)

const (
assertionLineNo = iota
assertionFunction

assertionMarker = "reason: Assertion"
)
const (
header = iota
register0
register0 = iota
register1
register2
register3
Expand Down Expand Up @@ -62,11 +66,12 @@ func main() {
if line == "" {
continue
}
if strings.HasPrefix(line, "Last software reset") {
isAssertion = strings.Contains(line, "reason: Assertion")
if strings.HasPrefix(line, lastSoftwareResetHeader) {
isAssertion = strings.Contains(line, assertionMarker)
continue
}
if strings.HasPrefix(line, "Stack:") {
if strings.HasPrefix(line, stackHeader) {
line = strings.TrimSpace(strings.TrimPrefix(line, stackHeader))
stackElems := strings.Fields(line)
var faultElem string
if isAssertion {
Expand Down Expand Up @@ -150,15 +155,15 @@ func getFailingBlock(mapFile string, faultedAddress uint64) ([]string, uint64, e

addressOfLine, err = strconv.ParseUint(addressField, 16, 64)
if err != nil {
return nil, 0, errors.New(fmt.Sprintf("Could not parse line: %s", mapLine))
return nil, 0, fmt.Errorf("Could not parse line: %s", mapLine)
}

if addressOfLine <= faultedAddress {

// Reset the slice of lines if we see a new address
if addressOfLine != lastAddress {
lastAddress = addressOfLine
faultLocation = make([]string, 0, 0)
faultLocation = make([]string, 0)
faultLocation = append(faultLocation, prevFaultFunction)
}
faultLocation = append(faultLocation, mapLine)
Expand Down
Binary file modified Tools/stackanalyzer/win/stackanalyzer.exe
Binary file not shown.
68 changes: 34 additions & 34 deletions src/Accelerometers/Accelerometers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,16 +58,16 @@ static unsigned int GetDecimalPlaces(uint8_t dataResolution) noexcept
#include "LISAccelerometer.h"

constexpr size_t AccelerometerTaskStackWords = 400; // big enough to handle printf and file writes
static Task<AccelerometerTaskStackWords> *accelerometerTask;
static Task<AccelerometerTaskStackWords> *_ecv_null accelerometerTask;

static LISAccelerometer *accelerometer = nullptr;
static LISAccelerometer *_ecv_null accelerometer = nullptr;

static uint16_t samplingRate = 0; // 0 means use the default
static volatile uint32_t numSamplesRequested;
static uint8_t resolution = DefaultAccelerometerResolution;
static uint8_t orientation = DefaultAccelerometerOrientation;
static volatile uint8_t axesRequested;
static FileStore* volatile accelerometerFile = nullptr; // this is non-null when the accelerometer is running, null otherwise
static FileStore *_ecv_null volatile accelerometerFile = nullptr; // this is non-null when the accelerometer is running, null otherwise
static unsigned int numLocalRunsCompleted = 0;
static unsigned int lastRunNumSamplesReceived = 0;
static uint8_t axisLookup[3];
Expand All @@ -91,7 +91,7 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
uint8_t rslt = 0;
for (unsigned int i = 0; i < 3; ++i)
{
if (axes & (1u << i))
if ((axes & (1u << i)) != 0)
{
rslt |= 1u << axisLookup[i];
}
Expand All @@ -104,7 +104,7 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
for (;;)
{
TaskBase::TakeIndexed(NotifyIndices::AccelerometerDataCollector);
FileStore * f = accelerometerFile; // capture volatile variable
FileStore *_ecv_null f = accelerometerFile; // capture volatile variable
if (f != nullptr)
{
// Collect and write the samples
Expand All @@ -115,22 +115,22 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
const int decimalPlaces = GetDecimalPlaces(resolution);
bool recordFailedStart = false;

if (accelerometer->StartCollecting(TranslateAxes(axesRequested)))
if (not_null(accelerometer)->StartCollecting(TranslateAxes(axesRequested)))
{
successfulStart = true;
uint16_t dataRate = 0;
do
{
const uint16_t *data;
const uint16_t *_ecv_array data;
bool overflowed;
unsigned int samplesRead = accelerometer->CollectData(&data, dataRate, overflowed);
unsigned int samplesRead = not_null(accelerometer)->CollectData(&data, dataRate, overflowed);
if (samplesRead == 0)
{
// samplesRead == 0 indicates an error, e.g. no interrupt
samplesWanted = 0;
f->Write("Failed to collect data from accelerometer\n");
f->Truncate(); // truncate the file in case we didn't write all the preallocated space
f->Close();
not_null(f)->Write("Failed to collect data from accelerometer\n");
not_null(f)->Truncate(); // truncate the file in case we didn't write all the preallocated space
not_null(f)->Close();
f = nullptr;
AddLocalAccelerometerRun(0);
}
Expand Down Expand Up @@ -159,7 +159,7 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept

for (unsigned int axis = 0; axis < 3; ++axis)
{
if (axesRequested & (1u << axis))
if ((axesRequested & (1u << axis)) != 0)
{
uint16_t dataVal = data[axisLookup[axis]];
if (axisInverted[axis])
Expand All @@ -169,7 +169,7 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
dataVal >>= (16u - resolution); // data from LIS3DH is left justified

// Sign-extend it
if (dataVal & (1u << (resolution - 1)))
if ((dataVal & (1u << (resolution - 1))) != 0)
{
dataVal |= ~mask;
}
Expand All @@ -185,7 +185,7 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
data += 3;

temp.cat('\n');
f->Write(temp.c_str());
not_null(f)->Write(temp.c_str());

--samplesRead;
--samplesWanted;
Expand All @@ -198,26 +198,26 @@ static uint8_t TranslateAxes(uint8_t axes) noexcept
{
String<StringLength50> temp;
temp.printf("Rate %u, overflows %u\n", dataRate, numOverflows);
f->Write(temp.c_str());
not_null(f)->Write(temp.c_str());
}
}
else
{
recordFailedStart = true;
if (f != nullptr)
{
f->Write("Failed to start accelerometer\n");
not_null(f)->Write("Failed to start accelerometer\n");
}
}

if (f != nullptr)
{
f->Truncate(); // truncate the file in case we didn't write all the preallocated space
f->Close();
not_null(f)->Truncate(); // truncate the file in case we didn't write all the preallocated space
not_null(f)->Close();
AddLocalAccelerometerRun(samplesWritten);
}

accelerometer->StopCollecting();
not_null(accelerometer)->StopCollecting();

// Wait for another command
accelerometerFile = nullptr;
Expand Down Expand Up @@ -247,7 +247,7 @@ static bool TranslateOrientation(uint32_t input) noexcept
const uint8_t yOrientation = 3u - xOrientation - zOrientation;

// The total number of inversions must be even if the cyclic order of the axes is 012, odd if it is 210 (can we prove this?)
if ((xOrientation + 1) % 3 != yOrientation)
if ((uint8_t)((xOrientation + 1u) % 3u) != yOrientation)
{
yInverted ^= 0x04; // we need an odd number of axis inversions
}
Expand Down Expand Up @@ -330,7 +330,7 @@ GCodeResult Accelerometers::ConfigureAccelerometer(GCodeBuffer& gb, const String
if (accelerometerTask == nullptr)
{
accelerometerTask = new Task<AccelerometerTaskStackWords>;
accelerometerTask->Create(AccelerometerTaskCode, "ACCEL", nullptr, TaskPriority::Accelerometer);
not_null(accelerometerTask)->Create(AccelerometerTaskCode, "ACCEL", nullptr, TaskPriority::Accelerometer);
}
}
else
Expand Down Expand Up @@ -359,7 +359,7 @@ GCodeResult Accelerometers::ConfigureAccelerometer(GCodeBuffer& gb, const String

if (seen)
{
if (!accelerometer->Configure(samplingRate, resolution))
if (!not_null(accelerometer)->Configure(samplingRate, resolution))
{
reply.copy("Failed to configure accelerometer");
return GCodeResult::error;
Expand Down Expand Up @@ -389,7 +389,7 @@ GCodeResult Accelerometers::ConfigureAccelerometer(GCodeBuffer& gb, const String
CanInterface::GetCanAddress(), 0, accelerometer->GetTypeName(), orientation, samplingRate, resolution, accelerometer->GetFrequency());
# else
reply.printf("Accelerometer %u type %s with orientation %u samples at %uHz with %u-bit resolution, SPI frequency %" PRIu32,
0, accelerometer->GetTypeName(), orientation, samplingRate, resolution, accelerometer->GetFrequency());
0, not_null(accelerometer)->GetTypeName(), orientation, samplingRate, resolution, not_null(accelerometer)->GetFrequency());
# endif
}
return GCodeResult::ok;
Expand Down Expand Up @@ -452,9 +452,9 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef&
}
else
{
const time_t time = reprap.GetPlatform().GetDateTime();
const time_t currentTime = reprap.GetPlatform().GetDateTime();
tm timeInfo;
gmtime_r(&time, &timeInfo);
gmtime_r(&currentTime, &timeInfo);
accelerometerFileName.printf("0:/sys/accelerometer/%u_%04u-%02u-%02u_%02u.%02u.%02u.csv",
# if SUPPORT_CAN_EXPANSION
(unsigned int)device.boardAddress,
Expand All @@ -463,7 +463,7 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef&
# endif
timeInfo.tm_year + 1900, timeInfo.tm_mon + 1, timeInfo.tm_mday, timeInfo.tm_hour, timeInfo.tm_min, timeInfo.tm_sec);
}
FileStore * const f = MassStorage::OpenFile(accelerometerFileName.c_str(), OpenMode::write, preallocSize);
FileStore *_ecv_null const f = MassStorage::OpenFile(accelerometerFileName.c_str(), OpenMode::write, preallocSize);
if (f == nullptr)
{
reply.copy("Failed to create accelerometer data file");
Expand All @@ -484,11 +484,11 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef&
{
String<StringLength50> temp;
temp.printf("Sample");
if (axes & 1u) { temp.cat(",X"); }
if (axes & 2u) { temp.cat(",Y"); }
if (axes & 4u) { temp.cat(",Z"); }
if ((axes & 1u) != 0) { temp.cat(",X"); }
if ((axes & 2u) != 0) { temp.cat(",Y"); }
if ((axes & 4u) != 0) { temp.cat(",Z"); }
temp.cat('\n');
f->Write(temp.c_str());
not_null(f)->Write(temp.c_str());
}

# if SUPPORT_CAN_EXPANSION
Expand All @@ -515,7 +515,7 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef&
successfulStart = false;
failedStart = false;
accelerometerFile = f;
accelerometerTask->Give(NotifyIndices::AccelerometerDataCollector);
not_null(accelerometerTask)->Give(NotifyIndices::AccelerometerDataCollector);
const uint32_t startTime = millis();
do
{
Expand All @@ -527,13 +527,13 @@ GCodeResult Accelerometers::StartAccelerometer(GCodeBuffer& gb, const StringRef&
} while (!failedStart && millis() - startTime < 1000);

reply.copy("Failed to start accelerometer data collection");
if (accelerometer->HasInterruptError())
if (not_null(accelerometer)->HasInterruptError())
{
reply.cat(": INT1 error");
}
if (accelerometerFile != nullptr)
{
accelerometerFile->Close();
not_null(accelerometerFile)->Close();
accelerometerFile = nullptr;
(void)MassStorage::Delete(accelerometerFileName.GetRef(), ErrorMessageMode::messageAlways);
}
Expand Down Expand Up @@ -564,7 +564,7 @@ void Accelerometers::Exit() noexcept
{
if (accelerometerTask != nullptr)
{
accelerometerTask->TerminateAndUnlink();
not_null(accelerometerTask)->TerminateAndUnlink();
accelerometerTask = nullptr;
}
}
Expand Down
4 changes: 2 additions & 2 deletions src/Accelerometers/LISAccelerometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,7 @@ bool LISAccelerometer:: StartCollecting(uint8_t axes) noexcept
}

// Collect some data from the FIFO, suspending until the data is available
unsigned int LISAccelerometer::CollectData(const uint16_t **collectedData, uint16_t &dataRate, bool &overflowed) noexcept
unsigned int LISAccelerometer::CollectData(const uint16_t *_ecv_array *collectedData, uint16_t &dataRate, bool &overflowed) noexcept
{
// Wait until we have some data
taskWaiting = TaskBase::GetCallerTaskHandle();
Expand Down Expand Up @@ -319,7 +319,7 @@ unsigned int LISAccelerometer::CollectData(const uint16_t **collectedData, uint1
return 0;
}

*collectedData = reinterpret_cast<const uint16_t*>(dataBuffer);
*collectedData = reinterpret_cast<const uint16_t* _ecv_array>(dataBuffer);
overflowed = (fifoStatus & 0x40) != 0;
const uint32_t interval = lastInterruptTime - firstInterruptTime;
dataRate = (totalNumRead == 0 || interval == 0)
Expand Down
4 changes: 2 additions & 2 deletions src/Accelerometers/LISAccelerometer.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class LISAccelerometer : public SharedSpiClient
bool StartCollecting(uint8_t axes) noexcept;

// Collect some data from the FIFO, suspending until the data is available
unsigned int CollectData(const uint16_t **collectedData, uint16_t &dataRate, bool &overflowed) noexcept;
unsigned int CollectData(const uint16_t *_ecv_array *collectedData, uint16_t &dataRate, bool &overflowed) noexcept;

// Stop collecting data
void StopCollecting() noexcept;
Expand Down Expand Up @@ -74,7 +74,7 @@ class LISAccelerometer : public SharedSpiClient
uint8_t ctrlReg_0x20;
Pin int1Pin;
alignas(2) uint8_t transferBuffer[2 + (6 * 32)]; // 1 dummy byte for alignment, one register address byte, 192 data bytes to read entire FIFO
uint8_t* const dataBuffer = transferBuffer + 2;
uint8_t *_ecv_array const dataBuffer = transferBuffer + 2;
};

#endif
Expand Down
8 changes: 4 additions & 4 deletions src/Config/Pins.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,14 @@
// Pins lookup functions, possibly hardware-dependent

// Return a pointer to the pin description entry. Declared in and called from CoreN2G. Return nullptr if the pin number is out of range.
const PinDescriptionBase *AppGetPinDescription(Pin p) noexcept
const PinDescriptionBase *_ecv_from _ecv_null AppGetPinDescription(Pin p) noexcept
{
return (p < ARRAY_SIZE(PinTable)) ? &PinTable[p] : nullptr;
}

// Function to look up a pin name and pass back the corresponding index into the pin table
// On this platform, the mapping from pin names to pins is fixed, so this is a simple lookup
bool LookupPinName(const char *pn, LogicalPin &lpin, bool &hardwareInverted) noexcept
bool LookupPinName(const char *_ecv_array pn, LogicalPin &lpin, bool &hardwareInverted) noexcept
{
if (StringEqualsIgnoreCase(pn, NoPinName))
{
Expand All @@ -28,15 +28,15 @@ bool LookupPinName(const char *pn, LogicalPin &lpin, bool &hardwareInverted) noe

for (size_t lp = 0; lp < ARRAY_SIZE(PinTable); ++lp)
{
const char *q = PinTable[lp].pinNames;
const char *_ecv_array _ecv_null q = PinTable[lp].pinNames;
if (q == nullptr)
{
continue;
}
while (*q != 0)
{
// Try the next alias in the list of names for this pin
const char *p = pn;
const char *_ecv_array p = pn;
bool hwInverted = (*q == '!');
if (hwInverted)
{
Expand Down
2 changes: 1 addition & 1 deletion src/Config/Pins_Duet3Mini.h
Original file line number Diff line number Diff line change
Expand Up @@ -502,7 +502,7 @@ constexpr DmaPriority DmacPrioTmcTx = 0;
constexpr DmaPriority DmacPrioTmcRx = 1; // the baud rate is 100kbps so this is not very critical
constexpr DmaPriority DmacPrioWiFi = 2; // high speed SPI in slave mode
constexpr DmaPriority DmacPrioSbc = 2; // high speed SPI in slave mode
constexpr DmaPriority DmacPrioLed = 1; // QSPI in master mode
constexpr DmaPriority DmacPrioLed = 1; // QSPI in master mode

// Timer allocation
// TC2 and TC3 are used for step pulse generation and software timers
Expand Down
Loading

0 comments on commit 0fa98e5

Please sign in to comment.