mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-28 06:24:10 +01:00
Merged in LP626-fix-atlassian-build-pipeline (pull request #546)
LP-626 fix atlassian build pipeline -- update ARM toolchain to GCC-10.3 Approved-by: Vladimir Zidar
This commit is contained in:
commit
f70df08d0f
@ -1,11 +1,12 @@
|
||||
pipelines:
|
||||
default:
|
||||
- step:
|
||||
image: atlassian/default-image:3
|
||||
runs-on: self.hosted
|
||||
script:
|
||||
- add-apt-repository ppa:librepilot/tools -y
|
||||
- apt-get update -q
|
||||
- apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools
|
||||
- DEBIAN_FRONTEND=noninteractive apt-get install -y build-essential qtbase5-dev git curl libc6-i386 python2 python2.7-dev libqt5svg5-dev qt5-qmltooling-plugins libqt5webview5-dev qtscript5-dev libqt5serialport5-dev qtmultimedia5-dev libusb-1.0-0-dev libudev-dev pkg-config libsdl-dev libosgearth-dev qttools5-dev-tools
|
||||
- make build_sdk_install
|
||||
- make all_flight
|
||||
- make all_flight --jobs=6
|
||||
- make fw_resource
|
||||
- make gcs
|
||||
- make gcs --jobs=6
|
||||
|
@ -283,7 +283,7 @@ SystemAlarmsAlarmOptions AlarmsGetHighestSeverity()
|
||||
}
|
||||
|
||||
|
||||
static const char *const systemalarms_severity_names[] = {
|
||||
__attribute__((unused)) static const char *const systemalarms_severity_names[] = {
|
||||
[SYSTEMALARMS_ALARM_UNINITIALISED] = "UNINITIALISED",
|
||||
[SYSTEMALARMS_ALARM_OK] = "OK",
|
||||
[SYSTEMALARMS_ALARM_WARNING] = "WARNING",
|
||||
|
@ -148,6 +148,7 @@ int32_t configuration_check()
|
||||
{
|
||||
ADDSEVERITY(!gps_assisted);
|
||||
}
|
||||
// fall through
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_VELOCITYROAM:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_LAND:
|
||||
@ -195,11 +196,11 @@ int32_t configuration_check()
|
||||
ManualControlSettingsChannelMaxGet(&channelMax);
|
||||
switch (thrustType) {
|
||||
case SYSTEMSETTINGS_THRUSTCONTROL_THROTTLE:
|
||||
ADDSEVERITY(fabsf(channelMax.Throttle - channelMin.Throttle) > 300.0f);
|
||||
ADDSEVERITY(fabsf((float)(channelMax.Throttle - channelMin.Throttle)) > 300.0f);
|
||||
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
|
||||
break;
|
||||
case SYSTEMSETTINGS_THRUSTCONTROL_COLLECTIVE:
|
||||
ADDSEVERITY(fabsf(channelMax.Collective - channelMin.Collective) > 300.0f);
|
||||
ADDSEVERITY(fabsf((float)(channelMax.Collective - channelMin.Collective)) > 300.0f);
|
||||
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
|
||||
break;
|
||||
default:
|
||||
|
@ -128,7 +128,7 @@ CFLAGS += -fomit-frame-pointer
|
||||
CFLAGS += -Wall -Wextra
|
||||
CFLAGS += -Wfloat-equal -Wdouble-promotion
|
||||
CFLAGS += -Wshadow
|
||||
CFLAGS += -Werror
|
||||
CFLAGS += -Werror -Wno-address-of-packed-member
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
|
||||
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
|
||||
|
||||
|
@ -707,14 +707,14 @@ static void InitSystemIdent(bool loadDefaults)
|
||||
systemIdentSettings.Tau = u.systemIdentState.Tau;
|
||||
systemIdentSettings.GyroReadTimeAverage = u.systemIdentState.GyroReadTimeAverage;
|
||||
memcpy(&systemIdentSettings.Beta, &u.systemIdentState.Beta, sizeof(SystemIdentSettingsBetaData));
|
||||
systemIdentSettings.Complete = u.systemIdentState.Complete;
|
||||
systemIdentSettings.Complete = (SystemIdentSettingsCompleteOptions)u.systemIdentState.Complete;
|
||||
} else {
|
||||
// Tau, GyroReadTimeAverage, Beta, and the Complete flag get stored values
|
||||
// so the user can fly another battery to select and test PIDs with the slider/knob
|
||||
u.systemIdentState.Tau = systemIdentSettings.Tau;
|
||||
u.systemIdentState.GyroReadTimeAverage = systemIdentSettings.GyroReadTimeAverage;
|
||||
memcpy(&u.systemIdentState.Beta, &systemIdentSettings.Beta, sizeof(SystemIdentStateBetaData));
|
||||
u.systemIdentState.Complete = systemIdentSettings.Complete;
|
||||
u.systemIdentState.Complete = (SystemIdentStateCompleteOptions)systemIdentSettings.Complete;
|
||||
}
|
||||
SystemIdentStateSet(&u.systemIdentState);
|
||||
|
||||
|
@ -446,7 +446,7 @@ static void configure(uint16_t *bytes_to_send)
|
||||
// Skip and fall through to next step
|
||||
status->lastConfigSent++;
|
||||
}
|
||||
|
||||
// fall through
|
||||
case LAST_CONFIG_SENT_START + 3:
|
||||
if (status->currentSettings.enableGLONASS || status->currentSettings.enableGPS) {
|
||||
config_gnss(bytes_to_send);
|
||||
@ -456,7 +456,7 @@ static void configure(uint16_t *bytes_to_send)
|
||||
status->lastConfigSent++;
|
||||
}
|
||||
// in the else case we must fall through because we must send something each time because successful send is tested externally
|
||||
|
||||
// fall through
|
||||
case LAST_CONFIG_SENT_START + 4:
|
||||
config_sbas(bytes_to_send);
|
||||
break;
|
||||
@ -628,6 +628,7 @@ void gps_ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
// we can do that if we choose because we haven't sent any data in this state
|
||||
// break;
|
||||
|
||||
// fall through
|
||||
case INIT_STEP_SEND_MON_VER:
|
||||
build_request((UBXSentPacket_t *)&status->working_packet, UBX_CLASS_MON, UBX_ID_MON_VER, bytes_to_send);
|
||||
// keep timeouts running properly, we (will have) just sent a packet that generates a reply
|
||||
@ -649,6 +650,7 @@ void gps_ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
// break;
|
||||
|
||||
// if here, we have just verified that the baud rates are in sync (again)
|
||||
// fall through
|
||||
case INIT_STEP_RESET_GPS:
|
||||
// make sure we don't change the baud rate too soon and garble the packet being sent
|
||||
// even after pios says the buffer is empty, the serial port buffer still has data in it
|
||||
@ -716,6 +718,7 @@ void gps_ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
// break;
|
||||
|
||||
// Revo and GPS are both at 9600 baud
|
||||
// fall through
|
||||
case INIT_STEP_GPS_BAUD:
|
||||
// https://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8_ReceiverDescriptionProtocolSpec_%28UBX-13003221%29_Public.pdf
|
||||
// It is possible to change the current communications port settings using a UBX-CFG-CFG message. This could
|
||||
@ -847,6 +850,7 @@ void gps_ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
// break;
|
||||
|
||||
// the autoconfig has completed normally
|
||||
// fall through
|
||||
case INIT_STEP_PRE_DONE:
|
||||
#if defined(AUTOBAUD_CONFIGURE_STORE_AND_DISABLE)
|
||||
// determine if we need to disable autoconfig via the autoconfig==AUTOBAUDCONFIGSTOREANDDISABLE setting
|
||||
|
@ -597,6 +597,7 @@ void HandleBatteryFailsafe(uint8_t *position, FlightModeSettingsData *modeSettin
|
||||
*position = modeSettings->BatteryFailsafeSwitchPositions.Critical;
|
||||
break;
|
||||
}
|
||||
// fall through
|
||||
case BATTERYFAILSAFE_WARNING:
|
||||
if (modeSettings->BatteryFailsafeSwitchPositions.Warning != -1) {
|
||||
*position = modeSettings->BatteryFailsafeSwitchPositions.Warning;
|
||||
@ -646,37 +647,38 @@ static uint8_t isAssistedFlightMode(uint8_t position, uint8_t flightMode, Flight
|
||||
case STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_GPSASSIST:
|
||||
{
|
||||
// default to cruise control.
|
||||
FlightModeSettingsStabilization1SettingsOptions thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
|
||||
typedef FlightModeSettingsStabilization1SettingsOptions _tm;
|
||||
_tm thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
|
||||
|
||||
switch (flightMode) {
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
|
||||
thrustMode = modeSettings->Stabilization1Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization1Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
|
||||
thrustMode = modeSettings->Stabilization2Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization2Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
|
||||
thrustMode = modeSettings->Stabilization3Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization3Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
|
||||
thrustMode = modeSettings->Stabilization4Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization4Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
|
||||
thrustMode = modeSettings->Stabilization5Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization5Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
|
||||
thrustMode = modeSettings->Stabilization6Settings.Thrust;
|
||||
thrustMode = (_tm)modeSettings->Stabilization6Settings.Thrust;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_VELOCITYROAM:
|
||||
// we hard code the "GPS Assisted" PostionHold/Roam to use alt-vario which
|
||||
// is a more appropriate throttle mode. "GPSAssist" adds braking
|
||||
// and a better throttle management to the standard Position Hold.
|
||||
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
|
||||
thrustMode = (_tm)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
|
||||
thrustMode = (_tm)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
|
||||
break;
|
||||
|
||||
// other modes will use cruisecontrol as default
|
||||
|
@ -805,7 +805,7 @@ void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsign
|
||||
void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode)
|
||||
{
|
||||
// Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm
|
||||
unsigned int steep = abs(y1 - y0) > abs(x1 - x0);
|
||||
unsigned int steep = abs((int)(y1 - y0)) > abs((int)(x1 - x0));
|
||||
|
||||
if (steep) {
|
||||
SWAP(x0, y0);
|
||||
@ -816,7 +816,7 @@ void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1
|
||||
SWAP(y0, y1);
|
||||
}
|
||||
int deltax = x1 - x0;
|
||||
unsigned int deltay = abs(y1 - y0);
|
||||
unsigned int deltay = abs((int)(y1 - y0));
|
||||
int error = deltax / 2;
|
||||
int ystep;
|
||||
unsigned int y = y0;
|
||||
@ -884,7 +884,7 @@ void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsi
|
||||
omode = 1;
|
||||
imode = 0;
|
||||
}
|
||||
int steep = abs(y1 - y0) > abs(x1 - x0);
|
||||
int steep = abs((int)(y1 - y0)) > abs((int)(x1 - x0));
|
||||
if (steep) {
|
||||
SWAP(x0, y0);
|
||||
SWAP(x1, y1);
|
||||
@ -894,7 +894,7 @@ void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsi
|
||||
SWAP(y0, y1);
|
||||
}
|
||||
int deltax = x1 - x0;
|
||||
unsigned int deltay = abs(y1 - y0);
|
||||
unsigned int deltay = abs((int)(y1 - y0));
|
||||
int error = deltax / 2;
|
||||
int ystep;
|
||||
unsigned int y = y0;
|
||||
@ -1583,7 +1583,7 @@ void drawBattery(uint16_t x, uint16_t y, uint8_t battery, uint16_t size)
|
||||
|
||||
void printTime(uint16_t x, uint16_t y)
|
||||
{
|
||||
char temp[9] =
|
||||
char temp[12] =
|
||||
{ 0 };
|
||||
|
||||
sprintf(temp, "%02d:%02d:%02d", timex.hour, timex.min, timex.sec);
|
||||
|
@ -51,7 +51,7 @@ public:
|
||||
static FixedWingFlyController *instance()
|
||||
{
|
||||
if (!p_inst) {
|
||||
p_inst = new FixedWingAutoTakeoffController();
|
||||
p_inst = new FixedWingAutoTakeoffController;
|
||||
}
|
||||
return p_inst;
|
||||
}
|
||||
|
@ -94,14 +94,14 @@ void VtolAutoTakeoffController::Activate(void)
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
// We only allow takeoff if the state transition of disarmed to armed occurs
|
||||
// whilst in the autotake flight mode
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
FlightStatusData _flightStatus;
|
||||
FlightStatusGet(&_flightStatus);
|
||||
StabilizationDesiredData stabiDesired;
|
||||
StabilizationDesiredGet(&stabiDesired);
|
||||
|
||||
if (flightStatus.Armed) {
|
||||
if (_flightStatus.Armed) {
|
||||
// Are we inflight?
|
||||
if (stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT || flightStatus.ControlChain.PathPlanner == FLIGHTSTATUS_CONTROLCHAIN_TRUE) {
|
||||
if (stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT || _flightStatus.ControlChain.PathPlanner == FLIGHTSTATUS_CONTROLCHAIN_TRUE) {
|
||||
// ok assume already in flight and just enter position hold
|
||||
// if we are not actually inflight this will just be a violent autotakeoff
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD;
|
||||
@ -327,9 +327,9 @@ void VtolAutoTakeoffController::UpdateAutoPilot()
|
||||
switch (autotakeoffState) {
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (!flightStatus.Armed) {
|
||||
FlightStatusData _flightStatus;
|
||||
FlightStatusGet(&_flightStatus);
|
||||
if (!_flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
fsm->setControlState(autotakeoffState);
|
||||
}
|
||||
@ -337,9 +337,9 @@ void VtolAutoTakeoffController::UpdateAutoPilot()
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (flightStatus.Armed) {
|
||||
FlightStatusData _flightStatus;
|
||||
FlightStatusGet(&_flightStatus);
|
||||
if (_flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE;
|
||||
fsm->setControlState(autotakeoffState);
|
||||
}
|
||||
@ -360,11 +360,11 @@ void VtolAutoTakeoffController::UpdateAutoPilot()
|
||||
{
|
||||
ManualControlCommandData cmd;
|
||||
ManualControlCommandGet(&cmd);
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
FlightStatusData _flightStatus;
|
||||
FlightStatusGet(&_flightStatus);
|
||||
|
||||
// we do not do a takeoff abort in pathplanner mode
|
||||
if (flightStatus.ControlChain.PathPlanner != FLIGHTSTATUS_CONTROLCHAIN_TRUE &&
|
||||
if (_flightStatus.ControlChain.PathPlanner != FLIGHTSTATUS_CONTROLCHAIN_TRUE &&
|
||||
cmd.Throttle < AUTOTAKEOFF_THROTTLE_ABORT_LIMIT) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT;
|
||||
fsm->setControlState(autotakeoffState);
|
||||
@ -373,9 +373,9 @@ void VtolAutoTakeoffController::UpdateAutoPilot()
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (!flightStatus.Armed) {
|
||||
FlightStatusData _flightStatus;
|
||||
FlightStatusGet(&_flightStatus);
|
||||
if (!_flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
fsm->setControlState(autotakeoffState);
|
||||
}
|
||||
|
@ -260,6 +260,7 @@ static void pathPlannerTask()
|
||||
switch (pathAction.Command) {
|
||||
case PATHACTION_COMMAND_ONNOTCONDITIONNEXTWAYPOINT:
|
||||
endCondition = !endCondition;
|
||||
// fall through
|
||||
case PATHACTION_COMMAND_ONCONDITIONNEXTWAYPOINT:
|
||||
if (endCondition) {
|
||||
setWaypoint(waypointActive.Index + 1);
|
||||
@ -267,6 +268,7 @@ static void pathPlannerTask()
|
||||
break;
|
||||
case PATHACTION_COMMAND_ONNOTCONDITIONJUMPWAYPOINT:
|
||||
endCondition = !endCondition;
|
||||
// fall through
|
||||
case PATHACTION_COMMAND_ONCONDITIONJUMPWAYPOINT:
|
||||
if (endCondition) {
|
||||
if (pathAction.JumpDestination < 0) {
|
||||
@ -312,7 +314,7 @@ void updatePathDesired()
|
||||
pathDesired.End.East = waypoint.Position.East;
|
||||
pathDesired.End.Down = waypoint.Position.Down;
|
||||
pathDesired.EndingVelocity = waypoint.Velocity;
|
||||
pathDesired.Mode = pathAction.Mode;
|
||||
pathDesired.Mode = (PathDesiredModeOptions)pathAction.Mode;
|
||||
pathDesired.ModeParameters[0] = pathAction.ModeParameters[0];
|
||||
pathDesired.ModeParameters[1] = pathAction.ModeParameters[1];
|
||||
pathDesired.ModeParameters[2] = pathAction.ModeParameters[2];
|
||||
@ -677,8 +679,8 @@ static uint8_t conditionPointingTowardsNext()
|
||||
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
|
||||
// check if current position exactly matches nextWaipoint (in 2D space)
|
||||
|
||||
// check if current position exactly matches nextWaipoint (in 2D space)
|
||||
if ((fabsf(nextWaypoint.Position.North - positionState.North) < 1e-6f) && (fabsf(nextWaypoint.Position.East - positionState.East) < 1e-6f)) {
|
||||
return true;
|
||||
}
|
||||
|
@ -309,6 +309,7 @@ static void stabilizationInnerloopTask()
|
||||
}
|
||||
// IMPORTANT: deliberately no "break;" here, execution continues with regular RATE control loop to avoid code duplication!
|
||||
// keep order as it is, RATE must follow!
|
||||
// fall through
|
||||
case STABILIZATIONSTATUS_INNERLOOP_RATE:
|
||||
{
|
||||
// limit rate to maximum configured limits (once here instead of 5 times in outer loop)
|
||||
|
@ -610,7 +610,7 @@ static uint16_t frsky_pack_fuel(
|
||||
{
|
||||
uint8_t index = 0;
|
||||
|
||||
uint16_t level = lroundf(abs(fuel_level * 100));
|
||||
uint16_t level = lroundf(fabsf(fuel_level * 100));
|
||||
|
||||
// Use fixed levels here because documentation says so.
|
||||
if (level > 94) {
|
||||
|
@ -807,7 +807,7 @@ void update_telemetrydata()
|
||||
txt_armstate = txt_unknown;
|
||||
}
|
||||
|
||||
snprintf(telestate->statusline, sizeof(telestate->statusline), "%12s,%8s", txt_flightmode, txt_armstate);
|
||||
snprintf(telestate->statusline, sizeof(telestate->statusline), "%12s,%7s", txt_flightmode, txt_armstate);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -438,7 +438,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||
{
|
||||
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp");
|
||||
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : );
|
||||
}
|
||||
|
||||
|
||||
@ -465,7 +465,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||
{
|
||||
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp");
|
||||
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : );
|
||||
}
|
||||
|
||||
|
||||
|
@ -355,7 +355,7 @@ int8_t PIOS_ADXL345_ReadAndAccumulateSamples(struct pios_adxl345_data *data, uin
|
||||
PIOS_Instrumentation_TimeStart(counterUpd);
|
||||
#endif
|
||||
for (uint8_t i = 0; i < samples; i++) {
|
||||
uint8_t buf[7] = { 0 };
|
||||
uint8_t buf[8] = { 0 };
|
||||
uint8_t *rec = &buf[1];
|
||||
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
|
||||
buf[0] = ADXL_X0_ADDR | ADXL_MULTI_BIT | ADXL_READ_BIT; // Multibyte read starting at X0
|
||||
|
@ -295,6 +295,10 @@ int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud)
|
||||
|
||||
return 0;
|
||||
}
|
||||
void PIOS_COM_ChangeBaud_VoidWrapper(uint32_t com_id, uint32_t baud)
|
||||
{
|
||||
PIOS_COM_ChangeBaud(com_id, baud);
|
||||
}
|
||||
|
||||
int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate)
|
||||
{
|
||||
@ -337,6 +341,10 @@ int32_t PIOS_COM_SetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t state)
|
||||
|
||||
return 0;
|
||||
}
|
||||
void PIOS_COM_SetCtrlLine_VoidWrapper(uint32_t com_id, uint32_t mask, uint32_t state)
|
||||
{
|
||||
PIOS_COM_SetCtrlLine(com_id, mask, state);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set control lines associated with the port
|
||||
@ -827,12 +835,12 @@ void PIOS_COM_LinkComPair(uint32_t com1_id, uint32_t com2_id, bool link_ctrl_lin
|
||||
PIOS_COM_ASYNC_RegisterRxCallback(com2_id, PIOS_COM_LinkComPairRxCallback, com1_id);
|
||||
// Optionally link the control like and baudrate changes between the two.
|
||||
if (link_ctrl_line) {
|
||||
PIOS_COM_RegisterCtrlLineCallback(com1_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine, com2_id);
|
||||
PIOS_COM_RegisterCtrlLineCallback(com2_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine, com1_id);
|
||||
PIOS_COM_RegisterCtrlLineCallback(com1_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine_VoidWrapper, com2_id);
|
||||
PIOS_COM_RegisterCtrlLineCallback(com2_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine_VoidWrapper, com1_id);
|
||||
}
|
||||
if (link_baud_rate) {
|
||||
PIOS_COM_RegisterBaudRateCallback(com1_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud, com2_id);
|
||||
PIOS_COM_RegisterBaudRateCallback(com2_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud, com1_id);
|
||||
PIOS_COM_RegisterBaudRateCallback(com1_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud_VoidWrapper, com2_id);
|
||||
PIOS_COM_RegisterBaudRateCallback(com2_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud_VoidWrapper, com1_id);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -474,7 +474,7 @@ bool PIOS_MS56xx_driver_poll(__attribute__((unused)) uintptr_t context)
|
||||
case MS56XX_FSM_CALIBRATION:
|
||||
PIOS_MS56xx_ReadCalibrationData();
|
||||
/* fall through to MS56XX_FSM_TEMPERATURE */
|
||||
|
||||
// fall through
|
||||
case MS56XX_FSM_TEMPERATURE:
|
||||
PIOS_MS56xx_StartADC(MS56XX_CONVERSION_TYPE_TemperatureConv);
|
||||
next_state = MS56XX_FSM_PRESSURE;
|
||||
|
@ -139,7 +139,7 @@ struct pios_rfm22b_transition {
|
||||
};
|
||||
|
||||
// Must ensure these prefilled arrays match the define sizes
|
||||
static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
|
||||
__attribute__((unused)) static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,
|
||||
@ -155,7 +155,7 @@ static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE
|
||||
}; // 64 bytes
|
||||
|
||||
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = {
|
||||
__attribute__((unused)) static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = {
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2
|
||||
};
|
||||
|
||||
@ -388,7 +388,7 @@ static const uint8_t reg_72[] = { 0x30, 0x48, 0x48, 0x48, 0x48, 0x60, 0x90, 0xCD
|
||||
|
||||
static const uint8_t packet_time[] = { 80, 40, 25, 15, 13, 10, 8, 6, 5 };
|
||||
static const uint8_t packet_time_ppm[] = { 26, 25, 25, 15, 13, 10, 8, 6, 5 };
|
||||
static const uint8_t num_channels[] = { 32, 32, 32, 32, 32, 32, 32, 32, 32 };
|
||||
__attribute__((unused)) static const uint8_t num_channels[] = { 32, 32, 32, 32, 32, 32, 32, 32, 32 };
|
||||
|
||||
static struct pios_rfm22b_dev *g_rfm22b_dev = NULL;
|
||||
|
||||
|
@ -292,48 +292,48 @@ void PIOS_Video_Init(const struct pios_video_cfg *cfg)
|
||||
GPIO_Init(GPIOC, &initStruct);
|
||||
|
||||
/* SPI3 - MASKBUFFER */
|
||||
GPIO_Init(cfg->mask.sclk.gpio, (GPIO_InitTypeDef *)&(cfg->mask.sclk.init));
|
||||
GPIO_Init(cfg->mask.miso.gpio, (GPIO_InitTypeDef *)&(cfg->mask.miso.init));
|
||||
GPIO_Init(cfg->mask->sclk.gpio, (GPIO_InitTypeDef *)&(cfg->mask->sclk.init));
|
||||
GPIO_Init(cfg->mask->miso.gpio, (GPIO_InitTypeDef *)&(cfg->mask->miso.init));
|
||||
|
||||
/* SPI1 SLAVE FRAMEBUFFER */
|
||||
GPIO_Init(cfg->level.sclk.gpio, (GPIO_InitTypeDef *)&(cfg->level.sclk.init));
|
||||
GPIO_Init(cfg->level.miso.gpio, (GPIO_InitTypeDef *)&(cfg->level.miso.init));
|
||||
GPIO_Init(cfg->level->sclk.gpio, (GPIO_InitTypeDef *)&(cfg->level->sclk.init));
|
||||
GPIO_Init(cfg->level->miso.gpio, (GPIO_InitTypeDef *)&(cfg->level->miso.init));
|
||||
|
||||
if (cfg->mask.remap) {
|
||||
GPIO_PinAFConfig(cfg->mask.sclk.gpio,
|
||||
__builtin_ctz(cfg->mask.sclk.init.GPIO_Pin),
|
||||
cfg->mask.remap);
|
||||
GPIO_PinAFConfig(cfg->mask.miso.gpio,
|
||||
__builtin_ctz(cfg->mask.miso.init.GPIO_Pin),
|
||||
cfg->mask.remap);
|
||||
if (cfg->mask->remap) {
|
||||
GPIO_PinAFConfig(cfg->mask->sclk.gpio,
|
||||
__builtin_ctz(cfg->mask->sclk.init.GPIO_Pin),
|
||||
cfg->mask->remap);
|
||||
GPIO_PinAFConfig(cfg->mask->miso.gpio,
|
||||
__builtin_ctz(cfg->mask->miso.init.GPIO_Pin),
|
||||
cfg->mask->remap);
|
||||
}
|
||||
if (cfg->level.remap) {
|
||||
GPIO_PinAFConfig(cfg->level.sclk.gpio,
|
||||
__builtin_ctz(cfg->level.sclk.init.GPIO_Pin),
|
||||
cfg->level.remap);
|
||||
GPIO_PinAFConfig(cfg->level.miso.gpio,
|
||||
__builtin_ctz(cfg->level.miso.init.GPIO_Pin),
|
||||
cfg->level.remap);
|
||||
if (cfg->level->remap) {
|
||||
GPIO_PinAFConfig(cfg->level->sclk.gpio,
|
||||
__builtin_ctz(cfg->level->sclk.init.GPIO_Pin),
|
||||
cfg->level->remap);
|
||||
GPIO_PinAFConfig(cfg->level->miso.gpio,
|
||||
__builtin_ctz(cfg->level->miso.init.GPIO_Pin),
|
||||
cfg->level->remap);
|
||||
}
|
||||
|
||||
/* Initialize the SPI block */
|
||||
SPI_Init(cfg->level.regs, (SPI_InitTypeDef *)&(cfg->level.init));
|
||||
SPI_Init(cfg->mask.regs, (SPI_InitTypeDef *)&(cfg->mask.init));
|
||||
SPI_Init(cfg->level->regs, (SPI_InitTypeDef *)&(cfg->level->init));
|
||||
SPI_Init(cfg->mask->regs, (SPI_InitTypeDef *)&(cfg->mask->init));
|
||||
|
||||
/* Enable SPI */
|
||||
SPI_Cmd(cfg->level.regs, ENABLE);
|
||||
SPI_Cmd(cfg->mask.regs, ENABLE);
|
||||
SPI_Cmd(cfg->level->regs, ENABLE);
|
||||
SPI_Cmd(cfg->mask->regs, ENABLE);
|
||||
|
||||
/* Configure DMA for SPI Tx SLAVE Maskbuffer */
|
||||
DMA_Cmd(cfg->mask.dma.tx.channel, DISABLE);
|
||||
DMA_Init(cfg->mask.dma.tx.channel, (DMA_InitTypeDef *)&(cfg->mask.dma.tx.init));
|
||||
DMA_Cmd(cfg->mask->dma.tx.channel, DISABLE);
|
||||
DMA_Init(cfg->mask->dma.tx.channel, (DMA_InitTypeDef *)&(cfg->mask->dma.tx.init));
|
||||
|
||||
/* Configure DMA for SPI Tx SLAVE Framebuffer*/
|
||||
DMA_Cmd(cfg->level.dma.tx.channel, DISABLE);
|
||||
DMA_Init(cfg->level.dma.tx.channel, (DMA_InitTypeDef *)&(cfg->level.dma.tx.init));
|
||||
DMA_Cmd(cfg->level->dma.tx.channel, DISABLE);
|
||||
DMA_Init(cfg->level->dma.tx.channel, (DMA_InitTypeDef *)&(cfg->level->dma.tx.init));
|
||||
|
||||
/* Trigger interrupt when for half conversions too to indicate double buffer */
|
||||
DMA_ITConfig(cfg->level.dma.tx.channel, DMA_IT_TC, ENABLE);
|
||||
DMA_ITConfig(cfg->level->dma.tx.channel, DMA_IT_TC, ENABLE);
|
||||
|
||||
/* Configure and clear buffers */
|
||||
draw_buffer_level = buffer0_level;
|
||||
@ -347,16 +347,16 @@ void PIOS_Video_Init(const struct pios_video_cfg *cfg)
|
||||
|
||||
/* Configure DMA interrupt */
|
||||
|
||||
NVIC_Init(&cfg->level.dma.irq.init);
|
||||
NVIC_Init(&cfg->level->dma.irq.init);
|
||||
|
||||
/* Enable SPI interrupts to DMA */
|
||||
SPI_I2S_DMACmd(cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(cfg->mask->regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(cfg->level->regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
|
||||
mask_dma = DMA1;
|
||||
main_dma = DMA2;
|
||||
main_stream = cfg->level.dma.tx.channel;
|
||||
mask_stream = cfg->mask.dma.tx.channel;
|
||||
main_stream = cfg->level->dma.tx.channel;
|
||||
mask_stream = cfg->mask->dma.tx.channel;
|
||||
/* Configure the Video Line interrupt */
|
||||
PIOS_EXTI_Init(cfg->hsync);
|
||||
PIOS_EXTI_Init(cfg->vsync);
|
||||
@ -377,26 +377,26 @@ static void prepare_line(uint32_t line_num)
|
||||
|
||||
dev_cfg->pixel_timer.timer->CNT = dc;
|
||||
|
||||
DMA_ClearFlag(dev_cfg->mask.dma.tx.channel, DMA_FLAG_TCIF7 | DMA_FLAG_HTIF7 | DMA_FLAG_FEIF7 | DMA_FLAG_TEIF7);
|
||||
DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_FEIF5 | DMA_FLAG_TEIF5);
|
||||
DMA_ClearFlag(dev_cfg->mask->dma.tx.channel, DMA_FLAG_TCIF7 | DMA_FLAG_HTIF7 | DMA_FLAG_FEIF7 | DMA_FLAG_TEIF7);
|
||||
DMA_ClearFlag(dev_cfg->level->dma.tx.channel, DMA_FLAG_FEIF5 | DMA_FLAG_TEIF5);
|
||||
|
||||
// Load new line
|
||||
DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel, (uint32_t)&disp_buffer_level[buf_offset], DMA_Memory_0);
|
||||
DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel, (uint32_t)&disp_buffer_mask[buf_offset], DMA_Memory_0);
|
||||
DMA_MemoryTargetConfig(dev_cfg->level->dma.tx.channel, (uint32_t)&disp_buffer_level[buf_offset], DMA_Memory_0);
|
||||
DMA_MemoryTargetConfig(dev_cfg->mask->dma.tx.channel, (uint32_t)&disp_buffer_mask[buf_offset], DMA_Memory_0);
|
||||
|
||||
// Enable DMA, Slave first
|
||||
DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel, BUFFER_LINE_LENGTH);
|
||||
DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel, BUFFER_LINE_LENGTH);
|
||||
DMA_SetCurrDataCounter(dev_cfg->level->dma.tx.channel, BUFFER_LINE_LENGTH);
|
||||
DMA_SetCurrDataCounter(dev_cfg->mask->dma.tx.channel, BUFFER_LINE_LENGTH);
|
||||
|
||||
SPI_Cmd(dev_cfg->level.regs, ENABLE);
|
||||
SPI_Cmd(dev_cfg->mask.regs, ENABLE);
|
||||
SPI_Cmd(dev_cfg->level->regs, ENABLE);
|
||||
SPI_Cmd(dev_cfg->mask->regs, ENABLE);
|
||||
|
||||
/* Enable SPI interrupts to DMA */
|
||||
SPI_I2S_DMACmd(dev_cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(dev_cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(dev_cfg->mask->regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
SPI_I2S_DMACmd(dev_cfg->level->regs, SPI_I2S_DMAReq_Tx, ENABLE);
|
||||
|
||||
DMA_Cmd(dev_cfg->level.dma.tx.channel, ENABLE);
|
||||
DMA_Cmd(dev_cfg->mask.dma.tx.channel, ENABLE);
|
||||
DMA_Cmd(dev_cfg->level->dma.tx.channel, ENABLE);
|
||||
DMA_Cmd(dev_cfg->mask->dma.tx.channel, ENABLE);
|
||||
}
|
||||
reset_hsync_timers();
|
||||
}
|
||||
@ -417,27 +417,27 @@ static void flush_spi()
|
||||
|
||||
// Can't flush if clock not running
|
||||
while ((dev_cfg->pixel_timer.timer->CR1 & 0x0001) && (!level_stopped | !mask_stopped)) {
|
||||
level_empty |= SPI_I2S_GetFlagStatus(dev_cfg->level.regs, SPI_I2S_FLAG_TXE) == SET;
|
||||
mask_empty |= SPI_I2S_GetFlagStatus(dev_cfg->mask.regs, SPI_I2S_FLAG_TXE) == SET;
|
||||
level_empty |= SPI_I2S_GetFlagStatus(dev_cfg->level->regs, SPI_I2S_FLAG_TXE) == SET;
|
||||
mask_empty |= SPI_I2S_GetFlagStatus(dev_cfg->mask->regs, SPI_I2S_FLAG_TXE) == SET;
|
||||
|
||||
if (level_empty && !level_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == RESET) {
|
||||
SPI_Cmd(dev_cfg->level.regs, DISABLE);
|
||||
if (level_empty && !level_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->level->regs ,SPI_I2S_FLAG_BSY) == RESET) {
|
||||
SPI_Cmd(dev_cfg->level->regs, DISABLE);
|
||||
level_stopped = true;
|
||||
}
|
||||
|
||||
if (mask_empty && !mask_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == RESET) {
|
||||
SPI_Cmd(dev_cfg->mask.regs, DISABLE);
|
||||
if (mask_empty && !mask_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->mask->regs ,SPI_I2S_FLAG_BSY) == RESET) {
|
||||
SPI_Cmd(dev_cfg->mask->regs, DISABLE);
|
||||
mask_stopped = true;
|
||||
}
|
||||
}
|
||||
/*
|
||||
uint32_t i = 0;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;*/
|
||||
SPI_Cmd(dev_cfg->mask.regs, DISABLE);
|
||||
SPI_Cmd(dev_cfg->level.regs, DISABLE);
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->level->regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->mask->regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->level->regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;
|
||||
while(SPI_I2S_GetFlagStatus(dev_cfg->mask->regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;*/
|
||||
SPI_Cmd(dev_cfg->mask->regs, DISABLE);
|
||||
SPI_Cmd(dev_cfg->level->regs, DISABLE);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -446,8 +446,8 @@ static void flush_spi()
|
||||
void PIOS_VIDEO_DMA_Handler(void)
|
||||
{
|
||||
// Handle flags from stream channel
|
||||
if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel, DMA_FLAG_TCIF5)) { // whole double buffer filled
|
||||
DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_TCIF5);
|
||||
if (DMA_GetFlagStatus(dev_cfg->level->dma.tx.channel, DMA_FLAG_TCIF5)) { // whole double buffer filled
|
||||
DMA_ClearFlag(dev_cfg->level->dma.tx.channel, DMA_FLAG_TCIF5);
|
||||
if (gActiveLine < GRAPHICS_HEIGHT) {
|
||||
flush_spi();
|
||||
stop_hsync_timers();
|
||||
@ -461,12 +461,12 @@ void PIOS_VIDEO_DMA_Handler(void)
|
||||
stop_hsync_timers();
|
||||
|
||||
// STOP DMA, master first
|
||||
DMA_Cmd(dev_cfg->mask.dma.tx.channel, DISABLE);
|
||||
DMA_Cmd(dev_cfg->level.dma.tx.channel, DISABLE);
|
||||
DMA_Cmd(dev_cfg->mask->dma.tx.channel, DISABLE);
|
||||
DMA_Cmd(dev_cfg->level->dma.tx.channel, DISABLE);
|
||||
}
|
||||
gActiveLine++;
|
||||
} else if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel, DMA_FLAG_HTIF5)) {
|
||||
DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_HTIF5);
|
||||
} else if (DMA_GetFlagStatus(dev_cfg->level->dma.tx.channel, DMA_FLAG_HTIF5)) {
|
||||
DMA_ClearFlag(dev_cfg->level->dma.tx.channel, DMA_FLAG_HTIF5);
|
||||
} else {}
|
||||
}
|
||||
|
||||
|
@ -36,8 +36,8 @@
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
struct pios_video_cfg {
|
||||
const struct pios_spi_cfg mask;
|
||||
const struct pios_spi_cfg level;
|
||||
const struct pios_spi_cfg *mask;
|
||||
const struct pios_spi_cfg *level;
|
||||
|
||||
const struct pios_exti_cfg *hsync;
|
||||
const struct pios_exti_cfg *vsync;
|
||||
|
@ -438,7 +438,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||
{
|
||||
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp");
|
||||
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : );
|
||||
}
|
||||
|
||||
|
||||
@ -465,7 +465,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
|
||||
*/
|
||||
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||
{
|
||||
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp");
|
||||
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : );
|
||||
}
|
||||
|
||||
|
||||
|
@ -539,6 +539,7 @@ static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
return -2; /* do not allow dsm bind on port with inverter */
|
||||
}
|
||||
#endif /* otherwise, return RXGPIO */
|
||||
// fall through
|
||||
case PIOS_IOCTL_USART_GET_RXGPIO:
|
||||
*(struct stm32_gpio *)param = usart_dev->cfg->rx;
|
||||
break;
|
||||
|
@ -2838,6 +2838,7 @@ void HRTIM_ADCTriggerConfig(HRTIM_TypeDef * HRTIMx,
|
||||
/* Set the ADC trigger 3 source */
|
||||
HRTIMx->HRTIM_COMMON.ADC3R = pADCTriggerCfg->Trigger;
|
||||
}
|
||||
break;
|
||||
case HRTIM_ADCTRIGGER_4:
|
||||
{
|
||||
HRTIM_cr1 &= ~(HRTIM_CR1_ADC4USRC);
|
||||
|
@ -1386,8 +1386,10 @@ void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK)
|
||||
break;
|
||||
case 0x05:
|
||||
RCC->CFGR3 &= ~RCC_CFGR3_TIM20SW;
|
||||
break;
|
||||
case 0x06:
|
||||
RCC->CFGR3 &= ~RCC_CFGR3_TIM2SW;
|
||||
break;
|
||||
case 0x07:
|
||||
RCC->CFGR3 &= ~RCC_CFGR3_TIM3SW;
|
||||
break;
|
||||
|
@ -405,7 +405,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -405,7 +405,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -405,7 +405,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -404,7 +404,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -405,7 +405,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -405,7 +405,7 @@ static void SetSysClock(void)
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
@ -180,7 +180,7 @@ USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev,
|
||||
fifo = pdev->regs.DFIFO[ch_ep_num];
|
||||
for (i = 0; i < count32b; i++, src+=4)
|
||||
{
|
||||
USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) );
|
||||
USB_OTG_WRITE_REG32( fifo, *((uint32_t *)src) );
|
||||
}
|
||||
}
|
||||
return status;
|
||||
@ -205,7 +205,7 @@ void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev,
|
||||
|
||||
for ( i = 0; i < count32b; i++, dest += 4 )
|
||||
{
|
||||
*(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo);
|
||||
*(uint32_t *)dest = USB_OTG_READ_REG32(fifo);
|
||||
|
||||
}
|
||||
return ((void *)dest);
|
||||
|
@ -595,6 +595,7 @@ static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
return -2; /* do not allow dsm bind on port with inverter */
|
||||
}
|
||||
#endif /* otherwise, return RXGPIO */
|
||||
// fall through
|
||||
case PIOS_IOCTL_USART_GET_RXGPIO:
|
||||
*(struct stm32_gpio *)param = usart_dev->cfg->rx;
|
||||
break;
|
||||
|
@ -112,7 +112,7 @@ static void default_cpu_handler(void)
|
||||
}
|
||||
|
||||
/** Prototype for optional exception vector handlers */
|
||||
#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_cpu_handler")))
|
||||
#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_cpu_handler"), noreturn))
|
||||
|
||||
/* standard CMSIS vector names */
|
||||
HANDLER(NMI_Handler);
|
||||
|
@ -607,154 +607,157 @@ static const struct pios_exti_cfg pios_exti_vsync_cfg __exti_config = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spi_cfg mask = {
|
||||
.regs = SPI3,
|
||||
.remap = GPIO_AF_SPI3,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_1Line_Tx,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_Low,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.irq = {
|
||||
// Note this is the stream ID that triggers interrupts (in this case RX)
|
||||
.flags = (DMA_IT_TCIF7),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Stream7_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
/*.rx = {},*/
|
||||
.tx = {
|
||||
.channel = DMA1_Stream7,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_0,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI3->DR),
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
|
||||
.DMA_BufferSize = BUFFER_LINE_LENGTH,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_VeryHigh,
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable,
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4,
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
/*.mosi = {},*/
|
||||
.slave_count = 1,
|
||||
};
|
||||
|
||||
static const struct pios_spi_cfg level = {
|
||||
.regs = SPI1,
|
||||
.remap = GPIO_AF_SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_1Line_Tx,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_Low,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.irq = {
|
||||
.flags = (DMA_IT_TCIF5),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA2_Stream5_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = 0,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
/*.rx = {},*/
|
||||
.tx = {
|
||||
.channel = DMA2_Stream5,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_3,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
|
||||
.DMA_BufferSize = BUFFER_LINE_LENGTH,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_VeryHigh,
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable,
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4,
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
/*.mosi = {},*/
|
||||
.slave_count = 1,
|
||||
};
|
||||
|
||||
static const struct pios_video_cfg pios_video_cfg = {
|
||||
.mask = {
|
||||
.regs = SPI3,
|
||||
.remap = GPIO_AF_SPI3,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_1Line_Tx,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_Low,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.irq = {
|
||||
// Note this is the stream ID that triggers interrupts (in this case RX)
|
||||
.flags = (DMA_IT_TCIF7),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Stream7_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
/*.rx = {},*/
|
||||
.tx = {
|
||||
.channel = DMA1_Stream7,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_0,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI3->DR),
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
|
||||
.DMA_BufferSize = BUFFER_LINE_LENGTH,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_VeryHigh,
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable,
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4,
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
/*.mosi = {},*/
|
||||
.slave_count = 1,
|
||||
},
|
||||
.level = {
|
||||
.regs = SPI1,
|
||||
.remap = GPIO_AF_SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Slave,
|
||||
.SPI_Direction = SPI_Direction_1Line_Tx,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_Low,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.irq = {
|
||||
.flags = (DMA_IT_TCIF5),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA2_Stream5_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = 0,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
/*.rx = {},*/
|
||||
.tx = {
|
||||
.channel = DMA2_Stream5,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_3,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
|
||||
.DMA_BufferSize = BUFFER_LINE_LENGTH,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_VeryHigh,
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable,
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4,
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
|
||||
},
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
/*.mosi = {},*/
|
||||
.slave_count = 1,
|
||||
},
|
||||
.mask = &mask,
|
||||
.level = &level,
|
||||
|
||||
.hsync = &pios_exti_hsync_cfg,
|
||||
.vsync = &pios_exti_vsync_cfg,
|
||||
|
||||
.pixel_timer = {
|
||||
.pixel_timer = {
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
@ -764,13 +767,13 @@ static const struct pios_video_cfg pios_video_cfg = {
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource6,
|
||||
.pin_source = GPIO_PinSource6,
|
||||
},
|
||||
.remap = GPIO_AF_TIM4,
|
||||
.remap = GPIO_AF_TIM4,
|
||||
},
|
||||
.hsync_capture = {
|
||||
.hsync_capture = {
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
@ -780,11 +783,11 @@ static const struct pios_video_cfg pios_video_cfg = {
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource7,
|
||||
.pin_source = GPIO_PinSource7,
|
||||
},
|
||||
.remap = GPIO_AF_TIM4,
|
||||
.remap = GPIO_AF_TIM4,
|
||||
},
|
||||
.tim_oc_init = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
|
@ -118,7 +118,7 @@ static const TIM_TimeBaseInitTypeDef tim_4_time_base = {
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg pios_tim4_cfg = {
|
||||
__attribute__((unused)) static const struct pios_tim_clock_cfg pios_tim4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_4_time_base,
|
||||
.irq = {
|
||||
|
@ -102,13 +102,13 @@ struct UAVOBase {
|
||||
bool isSettings : 1;
|
||||
bool isPriority : 1;
|
||||
} flags;
|
||||
} __attribute__((packed));
|
||||
} __attribute__((packed, aligned(4)));
|
||||
|
||||
/* Augmented type for Meta UAVO */
|
||||
struct UAVOMeta {
|
||||
struct UAVOBase base;
|
||||
UAVObjMetadata instance0;
|
||||
} __attribute__((packed));
|
||||
} __attribute__((packed, aligned(4)));
|
||||
|
||||
/* Shared data structure for all data-carrying UAVObjects (UAVOSingle and UAVOMulti) */
|
||||
struct UAVOData {
|
||||
@ -130,7 +130,7 @@ struct UAVOSingle {
|
||||
* Additional space will be malloc'd here to hold the
|
||||
* the data for this instance.
|
||||
*/
|
||||
} __attribute__((packed));
|
||||
} __attribute__((packed, aligned(4)));
|
||||
|
||||
/* Part of a linked list of instances chained off of a multi instance UAVO. */
|
||||
struct UAVOMultiInst {
|
||||
@ -151,7 +151,7 @@ struct UAVOMulti {
|
||||
* Additional space will be malloc'd here to hold the
|
||||
* the data for instance 0.
|
||||
*/
|
||||
} __attribute__((packed));
|
||||
} __attribute__((packed, aligned(4)));
|
||||
|
||||
/** all information about a metaobject are hardcoded constants **/
|
||||
#define MetaNumBytes sizeof(UAVObjMetadata)
|
||||
|
@ -1,24 +1,26 @@
|
||||
if [ "$uname" = Linux ]
|
||||
then
|
||||
url_ext="linux.tar.bz2"
|
||||
url_ext="x86_64-linux.tar.bz2"
|
||||
tool_md5="2383e4eb4ea23f248d33adc70dc3227e"
|
||||
elif [ "$uname" = Darwin ]
|
||||
then
|
||||
url_ext="mac.tar.bz2"
|
||||
tool_md5="7f2a7b7b23797302a9d6182c6e482449"
|
||||
elif [ "$uname" = Windows ]
|
||||
then
|
||||
url_ext="win32.zip"
|
||||
tool_md5="2bc8f0c4c4659f8259c8176223eeafc1"
|
||||
depends=(7z)
|
||||
fi
|
||||
|
||||
pkgver=4.9_2015_q2_update
|
||||
pkgdate=20150609
|
||||
pkgver=10.3-2021.10
|
||||
_pkgver=${pkgver//_/-}
|
||||
_pkgvershort=${_pkgver%-*}
|
||||
_pkgvershort=${_pkgvershort/-q/q}
|
||||
|
||||
tool_url="https://launchpad.net/gcc-arm-embedded/${pkgver%%_*}/${_pkgver}/+download/${tool}-${_pkgvershort/./_}-${pkgdate}-${url_ext}"
|
||||
tool_md5_url="${tool_url}/+md5"
|
||||
tool_install_name="${tool}-${_pkgvershort/./_}"
|
||||
tool_url="https://developer.arm.com/-/media/Files/downloads/gnu-rm/${pkgver}/${tool}-${pkgver}-${url_ext}"
|
||||
#tool_install_name="${tool}-${_pkgvershort/./_}"
|
||||
tool_install_name="${tool}-${pkgver}"
|
||||
if [ "$uname" = Windows ]
|
||||
then
|
||||
tool_extract_dir=$tools_dir/$tool_install_name
|
||||
|
@ -191,7 +191,7 @@ function download_and_verify
|
||||
fi
|
||||
elif [ -n "${tool_md5:-}" ]
|
||||
then
|
||||
if [[ "$tool_md5"* != "$(cd "$downloads_dir" && md5sum "$downloaded_file")" ]]
|
||||
if [[ "${tool_md5:-} -" != "$(cd "$downloads_dir" && md5sum <"$downloaded_file")" ]]
|
||||
then
|
||||
mv -f "$downloaded_file"{,.rej} && \
|
||||
verified=false
|
||||
|
Loading…
Reference in New Issue
Block a user